diff --git a/ArduCopter/AP_ExternalControl_Copter.cpp b/ArduCopter/AP_ExternalControl_Copter.cpp index 94f740e97e42a1..398b99a9ac7e18 100644 --- a/ArduCopter/AP_ExternalControl_Copter.cpp +++ b/ArduCopter/AP_ExternalControl_Copter.cpp @@ -33,12 +33,13 @@ bool AP_ExternalControl_Copter::set_linear_velocity_and_yaw_rate(const Vector3f Sets the target orientation, angular velocity, angular acceleration and desired thrust in body frame */ -bool set_angular_goals(const Quaternion &orientation, const Vector3f &angular_velocity, const Vector3f &angular_acceleration, const float &thrust) +bool AP_ExternalControl_Copter::set_angular_goals(const Quaternion &orientation, const Vector3f &angular_velocity, const Vector3f &angular_acceleration, const float &thrust) { if (!ready_for_external_control()) { - return false + return false; } - copter.mode_guided.set_angle(orientation, angular_velocity, angular_acceleration, thrust, true) + copter.mode_guided.set_angle(orientation, angular_velocity, angular_acceleration, thrust, true); + return true; } bool AP_ExternalControl_Copter::ready_for_external_control() diff --git a/libraries/AP_DDS/Idl/ardupilot_msgs/msg/AngularVelandAccn.idl b/libraries/AP_DDS/Idl/ardupilot_msgs/msg/AngularVelandAccn.idl index 08614e0649304c..0be735e2d67abe 100644 --- a/libraries/AP_DDS/Idl/ardupilot_msgs/msg/AngularVelandAccn.idl +++ b/libraries/AP_DDS/Idl/ardupilot_msgs/msg/AngularVelandAccn.idl @@ -28,7 +28,7 @@ module custom_msgs { @verbatim (language="comment", text="Thrust represented as a single floating-point number. \ It describes the magnitude of the thrust force.") - floatgit thrust; + float thrust; }; }; };