mirror of
https://github.com/ArduPilot/ardupilot
synced 2025-02-22 15:53:56 -04:00
Mount_MAVLink: uses vehicle's sysid
This commit is contained in:
parent
e726a05f3b
commit
93ba2d2d32
@ -164,7 +164,7 @@ Vector3f AP_Gimbal::getGimbalRateDemVecGyroBias()
|
|||||||
|
|
||||||
void AP_Gimbal::send_control(mavlink_channel_t chan)
|
void AP_Gimbal::send_control(mavlink_channel_t chan)
|
||||||
{
|
{
|
||||||
mavlink_msg_gimbal_control_send(chan,_sysid, _compid,
|
mavlink_msg_gimbal_control_send(chan, mavlink_system.sysid, _compid,
|
||||||
gimbalRateDemVec.x, gimbalRateDemVec.y, gimbalRateDemVec.z);
|
gimbalRateDemVec.x, gimbalRateDemVec.y, gimbalRateDemVec.z);
|
||||||
}
|
}
|
||||||
|
|
||||||
|
@ -23,7 +23,7 @@ class AP_Gimbal
|
|||||||
{
|
{
|
||||||
public:
|
public:
|
||||||
//Constructor
|
//Constructor
|
||||||
AP_Gimbal(const AP_AHRS_NavEKF &ahrs, uint8_t sysid, uint8_t compid, const AP_Mount::gimbal_params &gimbalParams) :
|
AP_Gimbal(const AP_AHRS_NavEKF &ahrs, uint8_t compid, const AP_Mount::gimbal_params &gimbalParams) :
|
||||||
_ekf(ahrs),
|
_ekf(ahrs),
|
||||||
_ahrs(ahrs),
|
_ahrs(ahrs),
|
||||||
_gimbalParams(gimbalParams),
|
_gimbalParams(gimbalParams),
|
||||||
@ -31,7 +31,6 @@ public:
|
|||||||
yawRateFiltPole(10.0f),
|
yawRateFiltPole(10.0f),
|
||||||
yawErrorLimit(0.1f)
|
yawErrorLimit(0.1f)
|
||||||
{
|
{
|
||||||
_sysid = sysid;
|
|
||||||
_compid = compid;
|
_compid = compid;
|
||||||
}
|
}
|
||||||
|
|
||||||
@ -68,7 +67,6 @@ private:
|
|||||||
// reducing this makes the gimbal respond more to vehicle yaw disturbances
|
// reducing this makes the gimbal respond more to vehicle yaw disturbances
|
||||||
float const yawErrorLimit;
|
float const yawErrorLimit;
|
||||||
|
|
||||||
uint8_t _sysid;
|
|
||||||
uint8_t _compid;
|
uint8_t _compid;
|
||||||
|
|
||||||
void send_control(mavlink_channel_t chan);
|
void send_control(mavlink_channel_t chan);
|
||||||
|
@ -13,7 +13,7 @@
|
|||||||
AP_Mount_MAVLink::AP_Mount_MAVLink(AP_Mount &frontend, AP_Mount::mount_state &state, uint8_t instance) :
|
AP_Mount_MAVLink::AP_Mount_MAVLink(AP_Mount &frontend, AP_Mount::mount_state &state, uint8_t instance) :
|
||||||
AP_Mount_Backend(frontend, state, instance),
|
AP_Mount_Backend(frontend, state, instance),
|
||||||
_initialised(false),
|
_initialised(false),
|
||||||
_gimbal(frontend._ahrs, 1, MAV_COMP_ID_GIMBAL, _state._gimbalParams)
|
_gimbal(frontend._ahrs, MAV_COMP_ID_GIMBAL, _state._gimbalParams)
|
||||||
{}
|
{}
|
||||||
|
|
||||||
// init - performs any required initialisation for this instance
|
// init - performs any required initialisation for this instance
|
||||||
|
Loading…
Reference in New Issue
Block a user