File tree Expand file tree Collapse file tree 1 file changed +4
-4
lines changed
diff_drive_controller/src Expand file tree Collapse file tree 1 file changed +4
-4
lines changed Original file line number Diff line number Diff line change @@ -153,7 +153,7 @@ controller_interface::return_type DiffDriveController::update_reference_from_sub
153153 reference_interfaces_[1 ] = 0.0 ;
154154 }
155155 else if (
156- ! std::isnan (command_msg_ptr->twist .linear .x ) && ! std::isnan (command_msg_ptr->twist .angular .z ))
156+ std::isfinite (command_msg_ptr->twist .linear .x ) && std::isfinite (command_msg_ptr->twist .angular .z ))
157157 {
158158 reference_interfaces_[0 ] = command_msg_ptr->twist .linear .x ;
159159 reference_interfaces_[1 ] = command_msg_ptr->twist .angular .z ;
@@ -187,7 +187,7 @@ controller_interface::return_type DiffDriveController::update_and_write_commands
187187 double linear_command = reference_interfaces_[0 ];
188188 double angular_command = reference_interfaces_[1 ];
189189
190- if (std::isnan (linear_command) || std::isnan (angular_command))
190+ if (! std::isfinite (linear_command) || ! std::isfinite (angular_command))
191191 {
192192 // NaNs occur on initialization when the reference interfaces are not yet set
193193 return controller_interface::return_type::OK;
@@ -721,10 +721,10 @@ controller_interface::CallbackReturn DiffDriveController::configure_side(
721721 return controller_interface::CallbackReturn::SUCCESS;
722722}
723723
724- bool DiffDriveController::on_set_chained_mode (bool chained_mode)
724+ bool DiffDriveController::on_set_chained_mode (bool /* chained_mode*/ )
725725{
726726 // Always accept switch to/from chained mode
727- return true || chained_mode ;
727+ return true ;
728728}
729729
730730std::vector<hardware_interface::CommandInterface>
You can’t perform that action at this time.
0 commit comments