Browse Source

mavlink_receiver: use SET_GPS_GLOBAL_ORIGIN to set the origin

The message GPS_GLOBAL_ORIGIN is meant as a telemtry information message
to send out the components reference and not to set it. I had to switch
to listen to SET_GPS_GLOBAL_ORIGIN such that I can implement sending out
GPS_GLOBAL_ORIGIN.
release/1.12
Matthias Grob 4 years ago
parent
commit
c845265b1b
  1. 13
      src/modules/mavlink/mavlink_receiver.cpp
  2. 2
      src/modules/mavlink/mavlink_receiver.h

13
src/modules/mavlink/mavlink_receiver.cpp

@ -162,8 +162,8 @@ MavlinkReceiver::handle_message(mavlink_message_t *msg) @@ -162,8 +162,8 @@ MavlinkReceiver::handle_message(mavlink_message_t *msg)
handle_message_odometry(msg);
break;
case MAVLINK_MSG_ID_GPS_GLOBAL_ORIGIN:
handle_message_gps_global_origin(msg);
case MAVLINK_MSG_ID_SET_GPS_GLOBAL_ORIGIN:
handle_message_set_gps_global_origin(msg);
break;
case MAVLINK_MSG_ID_RADIO_STATUS:
@ -1218,17 +1218,16 @@ MavlinkReceiver::handle_message_set_actuator_control_target(mavlink_message_t *m @@ -1218,17 +1218,16 @@ MavlinkReceiver::handle_message_set_actuator_control_target(mavlink_message_t *m
}
void
MavlinkReceiver::handle_message_gps_global_origin(mavlink_message_t *msg)
MavlinkReceiver::handle_message_set_gps_global_origin(mavlink_message_t *msg)
{
mavlink_gps_global_origin_t origin;
mavlink_msg_gps_global_origin_decode(msg, &origin);
mavlink_set_gps_global_origin_t origin;
mavlink_msg_set_gps_global_origin_decode(msg, &origin);
if (!globallocalconverter_initialized()) {
if (!globallocalconverter_initialized() && (origin.target_system == _mavlink->get_system_id())) {
/* Set reference point conversion of local coordiantes <--> global coordinates */
globallocalconverter_init((double)origin.latitude * 1.0e-7, (double)origin.longitude * 1.0e-7,
(float)origin.altitude * 1.0e-3f, hrt_absolute_time());
_global_ref_timestamp = hrt_absolute_time();
}
}

2
src/modules/mavlink/mavlink_receiver.h

@ -150,7 +150,7 @@ private: @@ -150,7 +150,7 @@ private:
void handle_message_distance_sensor(mavlink_message_t *msg);
void handle_message_follow_target(mavlink_message_t *msg);
void handle_message_generator_status(mavlink_message_t *msg);
void handle_message_gps_global_origin(mavlink_message_t *msg);
void handle_message_set_gps_global_origin(mavlink_message_t *msg);
void handle_message_gps_rtcm_data(mavlink_message_t *msg);
void handle_message_heartbeat(mavlink_message_t *msg);
void handle_message_hil_gps(mavlink_message_t *msg);

Loading…
Cancel
Save