SITL: use distinct source system for gimbal

gimbal was sending mavlink into ArduPilot with the target system's own sysid/compid tuple.  ArduPilot was simply discarding these as its own messages being looped back to it
This commit is contained in:
Peter Barker 2024-07-18 11:22:56 +10:00 committed by Peter Barker
parent 16a9e53bdb
commit 2584cfd786
2 changed files with 6 additions and 3 deletions

View File

@ -237,7 +237,7 @@ void Gimbal::param_send(const struct gimbal_param *p)
param_value.param_type = MAV_PARAM_TYPE_REAL32;
uint16_t len = mavlink_msg_param_value_encode_status(vehicle_system_id,
vehicle_component_id,
gimbal_component_id,
&mavlink.status,
&msg, &param_value);
@ -364,7 +364,7 @@ void Gimbal::send_report(void)
heartbeat.custom_mode = 0;
len = mavlink_msg_heartbeat_encode_status(vehicle_system_id,
vehicle_component_id,
gimbal_component_id,
&mavlink.status,
&msg, &heartbeat);
@ -394,7 +394,7 @@ void Gimbal::send_report(void)
gimbal_report.joint_az = joint_angles.z;
len = mavlink_msg_gimbal_report_encode_status(vehicle_system_id,
vehicle_component_id,
gimbal_component_id,
&mavlink.status,
&msg, &gimbal_report);

View File

@ -113,6 +113,9 @@ private:
uint32_t param_send_last_ms;
uint8_t param_send_idx;
// component ID we send from:
const uint8_t gimbal_component_id = 154; // MAV_COMP_ID_GIMBAL
void send_report(void);
void param_send(const struct gimbal_param *p);
struct gimbal_param *param_find(const char *name);