mirror of https://github.com/ArduPilot/ardupilot
GCS_MAVLink: use gps singleton
This commit is contained in:
parent
a8aa6a7822
commit
269294754f
|
@ -161,8 +161,7 @@ public:
|
||||||
void send_rangefinder_downward(const RangeFinder &rangefinder) const;
|
void send_rangefinder_downward(const RangeFinder &rangefinder) const;
|
||||||
bool send_proximity(const AP_Proximity &proximity) const;
|
bool send_proximity(const AP_Proximity &proximity) const;
|
||||||
void send_ahrs2(AP_AHRS &ahrs);
|
void send_ahrs2(AP_AHRS &ahrs);
|
||||||
bool send_gps_raw(AP_GPS &gps);
|
void send_system_time();
|
||||||
void send_system_time(AP_GPS &gps);
|
|
||||||
void send_radio_in(uint8_t receiver_rssi);
|
void send_radio_in(uint8_t receiver_rssi);
|
||||||
void send_raw_imu(const AP_InertialSensor &ins, const Compass &compass);
|
void send_raw_imu(const AP_InertialSensor &ins, const Compass &compass);
|
||||||
void send_scaled_pressure(AP_Baro &barometer);
|
void send_scaled_pressure(AP_Baro &barometer);
|
||||||
|
@ -231,7 +230,6 @@ protected:
|
||||||
virtual Compass *get_compass() const = 0;
|
virtual Compass *get_compass() const = 0;
|
||||||
virtual class AP_Camera *get_camera() const = 0;
|
virtual class AP_Camera *get_camera() const = 0;
|
||||||
virtual AP_ServoRelayEvents *get_servorelayevents() const = 0;
|
virtual AP_ServoRelayEvents *get_servorelayevents() const = 0;
|
||||||
virtual AP_GPS *get_gps() const = 0;
|
|
||||||
virtual AP_AdvancedFailsafe *get_advanced_failsafe() const { return nullptr; };
|
virtual AP_AdvancedFailsafe *get_advanced_failsafe() const { return nullptr; };
|
||||||
virtual bool set_mode(uint8_t mode) = 0;
|
virtual bool set_mode(uint8_t mode) = 0;
|
||||||
virtual const AP_FWVersion &get_fwver() const = 0;
|
virtual const AP_FWVersion &get_fwver() const = 0;
|
||||||
|
|
|
@ -907,11 +907,11 @@ GCS_MAVLINK::update(uint32_t max_time_us)
|
||||||
/*
|
/*
|
||||||
send the SYSTEM_TIME message
|
send the SYSTEM_TIME message
|
||||||
*/
|
*/
|
||||||
void GCS_MAVLINK::send_system_time(AP_GPS &gps)
|
void GCS_MAVLINK::send_system_time()
|
||||||
{
|
{
|
||||||
mavlink_msg_system_time_send(
|
mavlink_msg_system_time_send(
|
||||||
chan,
|
chan,
|
||||||
gps.time_epoch_usec(),
|
AP::gps().time_epoch_usec(),
|
||||||
AP_HAL::millis());
|
AP_HAL::millis());
|
||||||
}
|
}
|
||||||
|
|
||||||
|
@ -1728,12 +1728,7 @@ void GCS_MAVLINK::handle_statustext(mavlink_message_t *msg)
|
||||||
|
|
||||||
void GCS_MAVLINK::handle_common_gps_message(mavlink_message_t *msg)
|
void GCS_MAVLINK::handle_common_gps_message(mavlink_message_t *msg)
|
||||||
{
|
{
|
||||||
AP_GPS *gps = get_gps();
|
AP::gps().handle_msg(msg);
|
||||||
if (gps == nullptr) {
|
|
||||||
return;
|
|
||||||
}
|
|
||||||
|
|
||||||
gps->handle_msg(msg);
|
|
||||||
}
|
}
|
||||||
|
|
||||||
|
|
||||||
|
@ -2206,36 +2201,31 @@ void GCS_MAVLINK::send_hwstatus()
|
||||||
|
|
||||||
bool GCS_MAVLINK::try_send_gps_message(const enum ap_message id)
|
bool GCS_MAVLINK::try_send_gps_message(const enum ap_message id)
|
||||||
{
|
{
|
||||||
AP_GPS *gps = get_gps();
|
|
||||||
if (gps == nullptr) {
|
|
||||||
return true;
|
|
||||||
}
|
|
||||||
|
|
||||||
bool ret = true;
|
bool ret = true;
|
||||||
switch(id) {
|
switch(id) {
|
||||||
case MSG_SYSTEM_TIME:
|
case MSG_SYSTEM_TIME:
|
||||||
CHECK_PAYLOAD_SIZE(SYSTEM_TIME);
|
CHECK_PAYLOAD_SIZE(SYSTEM_TIME);
|
||||||
send_system_time(*gps);
|
send_system_time();
|
||||||
ret = true;
|
ret = true;
|
||||||
break;
|
break;
|
||||||
case MSG_GPS_RAW:
|
case MSG_GPS_RAW:
|
||||||
CHECK_PAYLOAD_SIZE(GPS_RAW_INT);
|
CHECK_PAYLOAD_SIZE(GPS_RAW_INT);
|
||||||
gps->send_mavlink_gps_raw(chan);
|
AP::gps().send_mavlink_gps_raw(chan);
|
||||||
ret = true;
|
ret = true;
|
||||||
break;
|
break;
|
||||||
case MSG_GPS_RTK:
|
case MSG_GPS_RTK:
|
||||||
CHECK_PAYLOAD_SIZE(GPS_RTK);
|
CHECK_PAYLOAD_SIZE(GPS_RTK);
|
||||||
gps->send_mavlink_gps_rtk(chan, 0);
|
AP::gps().send_mavlink_gps_rtk(chan, 0);
|
||||||
ret = true;
|
ret = true;
|
||||||
break;
|
break;
|
||||||
case MSG_GPS2_RAW:
|
case MSG_GPS2_RAW:
|
||||||
CHECK_PAYLOAD_SIZE(GPS2_RAW);
|
CHECK_PAYLOAD_SIZE(GPS2_RAW);
|
||||||
gps->send_mavlink_gps2_raw(chan);
|
AP::gps().send_mavlink_gps2_raw(chan);
|
||||||
ret = true;
|
ret = true;
|
||||||
break;
|
break;
|
||||||
case MSG_GPS2_RTK:
|
case MSG_GPS2_RTK:
|
||||||
CHECK_PAYLOAD_SIZE(GPS2_RTK);
|
CHECK_PAYLOAD_SIZE(GPS2_RTK);
|
||||||
gps->send_mavlink_gps_rtk(chan, 1);
|
AP::gps().send_mavlink_gps_rtk(chan, 1);
|
||||||
ret = true;
|
ret = true;
|
||||||
break;
|
break;
|
||||||
default:
|
default:
|
||||||
|
|
|
@ -26,7 +26,6 @@ protected:
|
||||||
Compass *get_compass() const override { return nullptr; };
|
Compass *get_compass() const override { return nullptr; };
|
||||||
AP_Mission *get_mission() override { return nullptr; }
|
AP_Mission *get_mission() override { return nullptr; }
|
||||||
AP_Rally *get_rally() const override { return nullptr; };
|
AP_Rally *get_rally() const override { return nullptr; };
|
||||||
AP_GPS *get_gps() const override { return nullptr; };
|
|
||||||
AP_Camera *get_camera() const override { return nullptr; };
|
AP_Camera *get_camera() const override { return nullptr; };
|
||||||
AP_ServoRelayEvents *get_servorelayevents() const override { return nullptr; }
|
AP_ServoRelayEvents *get_servorelayevents() const override { return nullptr; }
|
||||||
const AP_FWVersion &get_fwver() const override { return fwver; }
|
const AP_FWVersion &get_fwver() const override { return fwver; }
|
||||||
|
|
|
@ -40,8 +40,6 @@ void GCS_MAVLINK::handle_serial_control(const mavlink_message_t *msg)
|
||||||
return;
|
return;
|
||||||
}
|
}
|
||||||
|
|
||||||
AP_GPS *gps = get_gps();
|
|
||||||
|
|
||||||
bool exclusive = (packet.flags & SERIAL_CONTROL_FLAG_EXCLUSIVE) != 0;
|
bool exclusive = (packet.flags & SERIAL_CONTROL_FLAG_EXCLUSIVE) != 0;
|
||||||
|
|
||||||
switch (packet.device) {
|
switch (packet.device) {
|
||||||
|
@ -55,17 +53,11 @@ void GCS_MAVLINK::handle_serial_control(const mavlink_message_t *msg)
|
||||||
break;
|
break;
|
||||||
case SERIAL_CONTROL_DEV_GPS1:
|
case SERIAL_CONTROL_DEV_GPS1:
|
||||||
stream = port = hal.uartB;
|
stream = port = hal.uartB;
|
||||||
if (gps == nullptr) {
|
AP::gps().lock_port(0, exclusive);
|
||||||
return;
|
|
||||||
}
|
|
||||||
gps->lock_port(0, exclusive);
|
|
||||||
break;
|
break;
|
||||||
case SERIAL_CONTROL_DEV_GPS2:
|
case SERIAL_CONTROL_DEV_GPS2:
|
||||||
stream = port = hal.uartE;
|
stream = port = hal.uartE;
|
||||||
if (gps == nullptr) {
|
AP::gps().lock_port(1, exclusive);
|
||||||
return;
|
|
||||||
}
|
|
||||||
gps->lock_port(1, exclusive);
|
|
||||||
break;
|
break;
|
||||||
case SERIAL_CONTROL_DEV_SHELL:
|
case SERIAL_CONTROL_DEV_SHELL:
|
||||||
stream = hal.util->get_shell_stream();
|
stream = hal.util->get_shell_stream();
|
||||||
|
|
|
@ -35,7 +35,6 @@ protected:
|
||||||
AP_Mission *get_mission() override { return nullptr; }
|
AP_Mission *get_mission() override { return nullptr; }
|
||||||
AP_Rally *get_rally() const override { return nullptr; }
|
AP_Rally *get_rally() const override { return nullptr; }
|
||||||
AP_ServoRelayEvents *get_servorelayevents() const override { return nullptr; }
|
AP_ServoRelayEvents *get_servorelayevents() const override { return nullptr; }
|
||||||
AP_GPS *get_gps() const override { return nullptr; };
|
|
||||||
AP_Camera *get_camera() const override { return nullptr; };
|
AP_Camera *get_camera() const override { return nullptr; };
|
||||||
uint8_t sysid_my_gcs() const override { return 1; }
|
uint8_t sysid_my_gcs() const override { return 1; }
|
||||||
bool set_mode(uint8_t mode) override { return false; };
|
bool set_mode(uint8_t mode) override { return false; };
|
||||||
|
|
Loading…
Reference in New Issue