Copter: change parameter order of guided_set_angle

I thought it might be slightly better to put the optional parameters at the end
No functional change
This commit is contained in:
Randy Mackay 2016-08-09 12:10:13 +09:00
parent 6dd4e1a2aa
commit 0ed5665193
3 changed files with 3 additions and 3 deletions

View File

@ -810,7 +810,7 @@ private:
bool guided_set_destination(const Location_Class& dest_loc);
void guided_set_velocity(const Vector3f& velocity);
void guided_set_destination_posvel(const Vector3f& destination, const Vector3f& velocity);
void guided_set_angle(const Quaternion &q, float yaw_rate_rads, bool use_yaw_rate, float climb_rate_cms);
void guided_set_angle(const Quaternion &q, float climb_rate_cms, bool use_yaw_rate, float yaw_rate_rads);
void guided_run();
void guided_takeoff_run();
void guided_pos_control_run();

View File

@ -1694,7 +1694,7 @@ void GCS_MAVLINK_Copter::handleMessage(mavlink_message_t* msg)
}
copter.guided_set_angle(Quaternion(packet.q[0],packet.q[1],packet.q[2],packet.q[3]),
packet.body_yaw_rate, use_yaw_rate, climb_rate_cms);
climb_rate_cms, use_yaw_rate, packet.body_yaw_rate);
break;
}

View File

@ -266,7 +266,7 @@ void Copter::guided_set_destination_posvel(const Vector3f& destination, const Ve
}
// set guided mode angle target
void Copter::guided_set_angle(const Quaternion &q, float yaw_rate_rads, bool use_yaw_rate, float climb_rate_cms)
void Copter::guided_set_angle(const Quaternion &q, float climb_rate_cms, bool use_yaw_rate, float yaw_rate_rads)
{
// check we are in velocity control mode
if (guided_mode != Guided_Angle) {