Skip to content

Commit

Permalink
change sysid and component id
Browse files Browse the repository at this point in the history
  • Loading branch information
haitomatic committed Nov 7, 2023
1 parent 58cf3a2 commit d3c32d6
Show file tree
Hide file tree
Showing 2 changed files with 6 additions and 6 deletions.
8 changes: 4 additions & 4 deletions src/gazebo_mavlink_interface.cpp
Original file line number Diff line number Diff line change
Expand Up @@ -281,9 +281,9 @@ void GazeboMavlinkInterface::PoseCallback(const gz::msgs::Pose_V &_msg){
hil_state_quat.alt = pose_position.z() * 1e3;

mavlink_message_t msg;
mavlink_msg_hil_state_quaternion_encode_chan(1, 200, MAVLINK_COMM_0, &msg, &hil_state_quat);
mavlink_msg_hil_state_quaternion_encode_chan(254, 25, MAVLINK_COMM_0, &msg, &hil_state_quat);
// Override default global mavlink channel status with instance specific status
mavlink_interface_->FinalizeOutgoingMessage(&msg, 1, 200,
mavlink_interface_->FinalizeOutgoingMessage(&msg, 254, 25,
MAVLINK_MSG_ID_HIL_STATE_QUATERNION_MIN_LEN,
MAVLINK_MSG_ID_HIL_STATE_QUATERNION_LEN,
MAVLINK_MSG_ID_HIL_STATE_QUATERNION_CRC);
Expand Down Expand Up @@ -369,9 +369,9 @@ void GazeboMavlinkInterface::GpsCallback(const gz::msgs::NavSat &_msg) {

// send HIL_GPS Mavlink msg
mavlink_message_t msg;
mavlink_msg_hil_gps_encode_chan(1, 200, MAVLINK_COMM_0, &msg, &hil_gps_msg);
mavlink_msg_hil_gps_encode_chan(254, 25, MAVLINK_COMM_0, &msg, &hil_gps_msg);
// Override default global mavlink channel status with instance specific status
mavlink_interface_->FinalizeOutgoingMessage(&msg, 1, 200,
mavlink_interface_->FinalizeOutgoingMessage(&msg, 254, 25,
MAVLINK_MSG_ID_HIL_GPS_MIN_LEN,
MAVLINK_MSG_ID_HIL_GPS_LEN,
MAVLINK_MSG_ID_HIL_GPS_CRC);
Expand Down
4 changes: 2 additions & 2 deletions src/mavlink_interface.cpp
Original file line number Diff line number Diff line change
Expand Up @@ -335,9 +335,9 @@ void MavlinkInterface::SendSensorMessages(uint64_t time_usec) {
sensor_msg_mutex_.unlock();

mavlink_message_t msg;
mavlink_msg_hil_sensor_encode_chan(1, 200, MAVLINK_COMM_0, &msg, &sensor_msg);
mavlink_msg_hil_sensor_encode_chan(254, 25, MAVLINK_COMM_0, &msg, &sensor_msg);
// Override default global mavlink channel status with instance specific status
FinalizeOutgoingMessage(&msg, 1, 200,
FinalizeOutgoingMessage(&msg, 254, 25,
MAVLINK_MSG_ID_HIL_SENSOR_MIN_LEN,
MAVLINK_MSG_ID_HIL_SENSOR_LEN,
MAVLINK_MSG_ID_HIL_SENSOR_CRC);
Expand Down

0 comments on commit d3c32d6

Please sign in to comment.