diff --git a/msg/RoverVelocitySetpoint.msg b/msg/RoverVelocitySetpoint.msg index 83ec173798..2628ea18c4 100644 --- a/msg/RoverVelocitySetpoint.msg +++ b/msg/RoverVelocitySetpoint.msg @@ -1,5 +1,5 @@ uint64 timestamp # time since system start (microseconds) float32 speed # [m/s] [-inf, inf] Speed setpoint (Backwards driving if negative) -float32 bearing # [rad] [-pi,pi] from North. +float32 bearing # [rad] [-pi,pi] from North. [invalid: NAN, speed is defined in body x direction] float32 yaw # [rad] [-pi, pi] (Mecanum only, Optional, defaults to current vehicle yaw) Vehicle yaw setpoint in NED frame diff --git a/src/modules/rover_ackermann/AckermannVelControl/AckermannVelControl.cpp b/src/modules/rover_ackermann/AckermannVelControl/AckermannVelControl.cpp index 3b6f0fa500..8d9bf88e8b 100644 --- a/src/modules/rover_ackermann/AckermannVelControl/AckermannVelControl.cpp +++ b/src/modules/rover_ackermann/AckermannVelControl/AckermannVelControl.cpp @@ -149,7 +149,7 @@ void AckermannVelControl::generateAttitudeAndThrottleSetpoint() rover_attitude_setpoint.yaw_setpoint = _vehicle_yaw; _rover_attitude_setpoint_pub.publish(rover_attitude_setpoint); - } else { + } else if (PX4_ISFINITE(_rover_velocity_setpoint.bearing)) { rover_attitude_setpoint_s rover_attitude_setpoint{}; rover_attitude_setpoint.timestamp = _timestamp; rover_attitude_setpoint.yaw_setpoint = _rover_velocity_setpoint.bearing; diff --git a/src/modules/rover_differential/DifferentialVelControl/DifferentialVelControl.cpp b/src/modules/rover_differential/DifferentialVelControl/DifferentialVelControl.cpp index 912510f83b..2f8e3c8885 100644 --- a/src/modules/rover_differential/DifferentialVelControl/DifferentialVelControl.cpp +++ b/src/modules/rover_differential/DifferentialVelControl/DifferentialVelControl.cpp @@ -140,10 +140,12 @@ void DifferentialVelControl::generateAttitudeAndThrottleSetpoint() } // Attitude Setpoint - rover_attitude_setpoint_s rover_attitude_setpoint{}; - rover_attitude_setpoint.timestamp = _timestamp; - rover_attitude_setpoint.yaw_setpoint = _rover_velocity_setpoint.bearing; - _rover_attitude_setpoint_pub.publish(rover_attitude_setpoint); + if (PX4_ISFINITE(_rover_velocity_setpoint.bearing)) { + rover_attitude_setpoint_s rover_attitude_setpoint{}; + rover_attitude_setpoint.timestamp = _timestamp; + rover_attitude_setpoint.yaw_setpoint = _rover_velocity_setpoint.bearing; + _rover_attitude_setpoint_pub.publish(rover_attitude_setpoint); + } // Throttle Setpoint const float heading_error = matrix::wrap_pi(_rover_velocity_setpoint.bearing - _vehicle_yaw); diff --git a/src/modules/rover_mecanum/MecanumVelControl/MecanumVelControl.cpp b/src/modules/rover_mecanum/MecanumVelControl/MecanumVelControl.cpp index e33ea5cafc..0f3140bc39 100644 --- a/src/modules/rover_mecanum/MecanumVelControl/MecanumVelControl.cpp +++ b/src/modules/rover_mecanum/MecanumVelControl/MecanumVelControl.cpp @@ -167,7 +167,7 @@ void MecanumVelControl::generateAttitudeAndThrottleSetpoint() float speed_body_x_setpoint{0.f}; float speed_body_y_setpoint{0.f}; - if (fabsf(_rover_velocity_setpoint.speed) > FLT_EPSILON) { + if (fabsf(_rover_velocity_setpoint.speed) > FLT_EPSILON && PX4_ISFINITE(_rover_velocity_setpoint.bearing)) { const Vector3f velocity_in_local_frame(_rover_velocity_setpoint.speed * cosf( _rover_velocity_setpoint.bearing), _rover_velocity_setpoint.speed * sinf(_rover_velocity_setpoint.bearing), 0.f); @@ -175,6 +175,9 @@ void MecanumVelControl::generateAttitudeAndThrottleSetpoint() speed_body_x_setpoint = velocity_in_body_frame(0); speed_body_y_setpoint = velocity_in_body_frame(1); + } else { + speed_body_x_setpoint = _rover_velocity_setpoint.speed; + speed_body_y_setpoint = 0.f; } if (_param_ro_max_thr_speed.get() > FLT_EPSILON) { // Adjust speed setpoints if infeasible