mirror of https://github.com/ArduPilot/ardupilot
Plane: eliminate global static GCS_MAVLINK::send_home_all
This commit is contained in:
parent
a4d167affe
commit
1be52495f1
|
@ -1462,7 +1462,7 @@ void GCS_MAVLINK_Plane::handleMessage(mavlink_message_t* msg)
|
|||
plane.ahrs.set_home(new_home_loc);
|
||||
plane.home_is_set = HOME_SET_NOT_LOCKED;
|
||||
plane.Log_Write_Home_And_Origin();
|
||||
GCS_MAVLINK::send_home_all(new_home_loc);
|
||||
gcs().send_home(new_home_loc);
|
||||
result = MAV_RESULT_ACCEPTED;
|
||||
gcs().send_text(MAV_SEVERITY_INFO, "Set HOME to %.6f %.6f at %um",
|
||||
(double)(new_home_loc.lat*1.0e-7f),
|
||||
|
@ -1953,7 +1953,7 @@ void GCS_MAVLINK_Plane::handleMessage(mavlink_message_t* msg)
|
|||
plane.ahrs.set_home(new_home_loc);
|
||||
plane.home_is_set = HOME_SET_NOT_LOCKED;
|
||||
plane.Log_Write_Home_And_Origin();
|
||||
GCS_MAVLINK::send_home_all(new_home_loc);
|
||||
gcs().send_home(new_home_loc);
|
||||
gcs().send_text(MAV_SEVERITY_INFO, "Set HOME to %.6f %.6f at %um",
|
||||
(double)(new_home_loc.lat*1.0e-7f),
|
||||
(double)(new_home_loc.lng*1.0e-7f),
|
||||
|
|
|
@ -17,6 +17,9 @@ public:
|
|||
GCS_MAVLINK_Plane &chan(const uint8_t ofs) override {
|
||||
return _chan[ofs];
|
||||
};
|
||||
const GCS_MAVLINK_Plane &chan(const uint8_t ofs) const override {
|
||||
return _chan[ofs];
|
||||
};
|
||||
|
||||
void send_airspeed_calibration(const Vector3f &vg);
|
||||
|
||||
|
|
|
@ -109,7 +109,7 @@ void Plane::init_home()
|
|||
ahrs.set_home(gps.location());
|
||||
home_is_set = HOME_SET_NOT_LOCKED;
|
||||
Log_Write_Home_And_Origin();
|
||||
GCS_MAVLINK::send_home_all(gps.location());
|
||||
gcs().send_home(gps.location());
|
||||
|
||||
// Save Home to EEPROM
|
||||
mission.write_home_to_storage();
|
||||
|
@ -138,7 +138,7 @@ void Plane::update_home()
|
|||
if(ahrs.get_position(loc)) {
|
||||
ahrs.set_home(loc);
|
||||
Log_Write_Home_And_Origin();
|
||||
GCS_MAVLINK::send_home_all(loc);
|
||||
gcs().send_home(loc);
|
||||
}
|
||||
}
|
||||
barometer.update_calibration();
|
||||
|
|
|
@ -905,7 +905,7 @@ void Plane::do_set_home(const AP_Mission::Mission_Command& cmd)
|
|||
ahrs.set_home(cmd.content.location);
|
||||
home_is_set = HOME_SET_NOT_LOCKED;
|
||||
Log_Write_Home_And_Origin();
|
||||
GCS_MAVLINK::send_home_all(cmd.content.location);
|
||||
gcs().send_home(cmd.content.location);
|
||||
}
|
||||
}
|
||||
|
||||
|
|
Loading…
Reference in New Issue