Cut case MAVLINK_MSG_ID_VISION_POSITION_ESTIMATE content and paste into handle_message_vision_position_estimate() method. Add const specifier to publish_odometry_topic() method.

This commit is contained in:
mcsauder
2019-03-05 10:41:31 -07:00
committed by Beat Küng
parent c3acd3bad3
commit 3918d0ce0a
2 changed files with 9 additions and 3 deletions

View File

@@ -302,7 +302,7 @@ void Simulator::handle_message(mavlink_message_t *msg)
case MAVLINK_MSG_ID_ODOMETRY:
case MAVLINK_MSG_ID_VISION_POSITION_ESTIMATE:
publish_odometry_topic(msg);
handle_message_vision_position_estimate(msg);
break;
case MAVLINK_MSG_ID_DISTANCE_SENSOR:
@@ -542,6 +542,11 @@ void Simulator::handle_message_rc_channels(const mavlink_message_t *msg)
}
}
void Simulator::handle_message_vision_position_estimate(const mavlink_message_t *msg)
{
publish_odometry_topic(msg);
}
void Simulator::send_mavlink_message(const mavlink_message_t &aMsg)
{
uint8_t buf[MAVLINK_MAX_PACKET_LEN];
@@ -1100,7 +1105,7 @@ int Simulator::publish_flow_topic(mavlink_hil_optical_flow_t *flow_mavlink)
return OK;
}
int Simulator::publish_odometry_topic(mavlink_message_t *odom_mavlink)
int Simulator::publish_odometry_topic(const mavlink_message_t *odom_mavlink)
{
uint64_t timestamp = hrt_absolute_time();