GCS_MAVLink: remove arguments to send_home and send_ekf_origin

This commit is contained in:
Peter Barker 2018-05-16 14:48:42 +10:00 committed by Peter Barker
parent 3e7cb08804
commit 217fd73100
3 changed files with 43 additions and 34 deletions

View File

@ -34,14 +34,14 @@ void GCS::send_named_float(const char *name, float value) const
FOR_EACH_ACTIVE_CHANNEL(send_named_float(name, value));
}
void GCS::send_home(const Location &home) const
void GCS::send_home() const
{
FOR_EACH_ACTIVE_CHANNEL(send_home(home));
FOR_EACH_ACTIVE_CHANNEL(send_home());
}
void GCS::send_ekf_origin(const Location &ekf_origin) const
void GCS::send_ekf_origin() const
{
FOR_EACH_ACTIVE_CHANNEL(send_ekf_origin(ekf_origin));
FOR_EACH_ACTIVE_CHANNEL(send_ekf_origin());
}
/*

View File

@ -186,8 +186,8 @@ public:
void send_local_position() const;
void send_vibration() const;
void send_named_float(const char *name, float value) const;
void send_home(const Location &home) const;
void send_ekf_origin(const Location &ekf_origin) const;
void send_home() const;
void send_ekf_origin() const;
void send_servo_output_raw(bool hil);
static void send_collision_all(const AP_Avoidance::Obstacle &threat, MAV_COLLISION_ACTION behaviour);
void send_accelcal_vehicle_position(uint32_t position);
@ -557,8 +557,8 @@ public:
void send_message(enum ap_message id);
void send_mission_item_reached_message(uint16_t mission_index);
void send_named_float(const char *name, float value) const;
void send_home(const Location &home) const;
void send_ekf_origin(const Location &ekf_origin) const;
void send_home() const;
void send_ekf_origin() const;
void send_parameter_value(const char *param_name,
ap_var_type param_type,

View File

@ -1566,32 +1566,44 @@ void GCS_MAVLINK::send_named_float(const char *name, float value) const
mavlink_msg_named_value_float_send(chan, AP_HAL::millis(), float_name, value);
}
void GCS_MAVLINK::send_home(const Location &home) const
void GCS_MAVLINK::send_home() const
{
if (HAVE_PAYLOAD_SPACE(chan, HOME_POSITION)) {
const float q[4] = {1.0f, 0.0f, 0.0f, 0.0f};
mavlink_msg_home_position_send(
chan,
home.lat,
home.lng,
home.alt * 10,
0.0f, 0.0f, 0.0f,
q,
0.0f, 0.0f, 0.0f,
AP_HAL::micros64());
if (!HAVE_PAYLOAD_SPACE(chan, HOME_POSITION)) {
return;
}
if (!AP::ahrs().home_is_set()) {
return;
}
Location home = AP::ahrs().get_home();
const float q[4] = {1.0f, 0.0f, 0.0f, 0.0f};
mavlink_msg_home_position_send(
chan,
home.lat,
home.lng,
home.alt * 10,
0.0f, 0.0f, 0.0f,
q,
0.0f, 0.0f, 0.0f,
AP_HAL::micros64());
}
void GCS_MAVLINK::send_ekf_origin(const Location &ekf_origin) const
void GCS_MAVLINK::send_ekf_origin() const
{
if (HAVE_PAYLOAD_SPACE(chan, GPS_GLOBAL_ORIGIN)) {
mavlink_msg_gps_global_origin_send(
chan,
ekf_origin.lat,
ekf_origin.lng,
ekf_origin.alt * 10,
AP_HAL::micros64());
if (!HAVE_PAYLOAD_SPACE(chan, GPS_GLOBAL_ORIGIN)) {
return;
}
Location ekf_origin;
if (!AP::ahrs().get_origin(ekf_origin)) {
return;
}
mavlink_msg_gps_global_origin_send(
chan,
ekf_origin.lat,
ekf_origin.lng,
ekf_origin.alt * 10,
AP_HAL::micros64());
}
/*
@ -1920,7 +1932,7 @@ void GCS_MAVLINK::set_ekf_origin(const Location& loc)
ahrs.Log_Write_Home_And_Origin();
// send ekf origin to GCS
send_ekf_origin(loc);
send_ekf_origin();
}
void GCS_MAVLINK::handle_set_gps_global_origin(const mavlink_message_t *msg)
@ -2482,12 +2494,9 @@ MAV_RESULT GCS_MAVLINK::handle_command_get_home_position(const mavlink_command_l
if (!AP::ahrs().home_is_set()) {
return MAV_RESULT_FAILED;
}
send_home(AP::ahrs().get_home());
send_home();
send_ekf_origin();
Location ekf_origin;
if (AP::ahrs().get_origin(ekf_origin)) {
send_ekf_origin(ekf_origin);
}
return MAV_RESULT_ACCEPTED;
}