mirror of
https://github.com/ArduPilot/ardupilot
synced 2025-01-03 06:28:27 -04:00
AP_Mount: Add MNTx_SYSID_DFLT param to easily target another vehicle
This commit is contained in:
parent
3d11ec7b5c
commit
47ad614e8e
@ -14,6 +14,7 @@ void AP_Mount_Alexmos::init()
|
|||||||
read_params(0); //we request parameters for profile 0 and therfore get global and profile parameters
|
read_params(0); //we request parameters for profile 0 and therfore get global and profile parameters
|
||||||
set_mode((enum MAV_MOUNT_MODE)_params.default_mode.get());
|
set_mode((enum MAV_MOUNT_MODE)_params.default_mode.get());
|
||||||
}
|
}
|
||||||
|
AP_Mount_Backend::init();
|
||||||
}
|
}
|
||||||
|
|
||||||
// update mount position - should be called periodically
|
// update mount position - should be called periodically
|
||||||
|
@ -7,6 +7,13 @@ extern const AP_HAL::HAL& hal;
|
|||||||
|
|
||||||
#define AP_MOUNT_UPDATE_DT 0.02 // update rate in seconds. update() should be called at this rate
|
#define AP_MOUNT_UPDATE_DT 0.02 // update rate in seconds. update() should be called at this rate
|
||||||
|
|
||||||
|
// Default init function for every mount
|
||||||
|
void AP_Mount_Backend::init()
|
||||||
|
{
|
||||||
|
// setting default target sysid from parameters
|
||||||
|
_target_sysid = _params.sysid_default.get();
|
||||||
|
}
|
||||||
|
|
||||||
// set angle target in degrees
|
// set angle target in degrees
|
||||||
// yaw_is_earth_frame (aka yaw_lock) should be true if yaw angle is earth-frame, false if body-frame
|
// yaw_is_earth_frame (aka yaw_lock) should be true if yaw angle is earth-frame, false if body-frame
|
||||||
void AP_Mount_Backend::set_angle_target(float roll_deg, float pitch_deg, float yaw_deg, bool yaw_is_earth_frame)
|
void AP_Mount_Backend::set_angle_target(float roll_deg, float pitch_deg, float yaw_deg, bool yaw_is_earth_frame)
|
||||||
|
@ -35,7 +35,7 @@ public:
|
|||||||
{}
|
{}
|
||||||
|
|
||||||
// init - performs any required initialisation for this instance
|
// init - performs any required initialisation for this instance
|
||||||
virtual void init() = 0;
|
virtual void init();
|
||||||
|
|
||||||
// update mount position - should be called periodically
|
// update mount position - should be called periodically
|
||||||
virtual void update() = 0;
|
virtual void update() = 0;
|
||||||
|
@ -18,9 +18,6 @@ public:
|
|||||||
// Constructor
|
// Constructor
|
||||||
using AP_Mount_Backend::AP_Mount_Backend;
|
using AP_Mount_Backend::AP_Mount_Backend;
|
||||||
|
|
||||||
// init
|
|
||||||
void init() override {}
|
|
||||||
|
|
||||||
// update mount position
|
// update mount position
|
||||||
void update() override;
|
void update() override;
|
||||||
|
|
||||||
|
@ -152,6 +152,12 @@ const AP_Param::GroupInfo AP_Mount_Params::var_info[] = {
|
|||||||
// @User: Standard
|
// @User: Standard
|
||||||
AP_GROUPINFO("_LEAD_PTCH", 13, AP_Mount_Params, pitch_stb_lead, 0.0f),
|
AP_GROUPINFO("_LEAD_PTCH", 13, AP_Mount_Params, pitch_stb_lead, 0.0f),
|
||||||
|
|
||||||
|
// @Param: _SYSID_DFLT
|
||||||
|
// @DisplayName: Mount Target sysID
|
||||||
|
// @Description: Default Target sysID for the mount to point to
|
||||||
|
// @RebootRequired: True
|
||||||
|
// @User: Standard
|
||||||
|
AP_GROUPINFO("_SYSID_DFLT", 14, AP_Mount_Params, sysid_default, 0),
|
||||||
AP_GROUPEND
|
AP_GROUPEND
|
||||||
};
|
};
|
||||||
|
|
||||||
|
@ -29,4 +29,5 @@ public:
|
|||||||
|
|
||||||
AP_Float roll_stb_lead; // roll lead control gain (only used by servo backend)
|
AP_Float roll_stb_lead; // roll lead control gain (only used by servo backend)
|
||||||
AP_Float pitch_stb_lead; // pitch lead control gain (only used by servo backend)
|
AP_Float pitch_stb_lead; // pitch lead control gain (only used by servo backend)
|
||||||
|
AP_Int8 sysid_default; // target sysid for mount to follow
|
||||||
};
|
};
|
||||||
|
@ -17,9 +17,6 @@ public:
|
|||||||
// Constructor
|
// Constructor
|
||||||
using AP_Mount_Backend::AP_Mount_Backend;
|
using AP_Mount_Backend::AP_Mount_Backend;
|
||||||
|
|
||||||
// init - performs any required initialisation for this instance
|
|
||||||
void init() override {}
|
|
||||||
|
|
||||||
// update mount position - should be called periodically
|
// update mount position - should be called periodically
|
||||||
void update() override;
|
void update() override;
|
||||||
|
|
||||||
|
@ -16,6 +16,7 @@ void AP_Mount_SToRM32_serial::init()
|
|||||||
_initialised = true;
|
_initialised = true;
|
||||||
set_mode((enum MAV_MOUNT_MODE)_params.default_mode.get());
|
set_mode((enum MAV_MOUNT_MODE)_params.default_mode.get());
|
||||||
}
|
}
|
||||||
|
AP_Mount_Backend::init();
|
||||||
|
|
||||||
}
|
}
|
||||||
|
|
||||||
|
@ -22,9 +22,6 @@ public:
|
|||||||
/* Do not allow copies */
|
/* Do not allow copies */
|
||||||
CLASS_NO_COPY(AP_Mount_Scripting);
|
CLASS_NO_COPY(AP_Mount_Scripting);
|
||||||
|
|
||||||
// init - performs any required initialisation for this instance
|
|
||||||
void init() override {};
|
|
||||||
|
|
||||||
// update mount position - should be called periodically
|
// update mount position - should be called periodically
|
||||||
void update() override;
|
void update() override;
|
||||||
|
|
||||||
|
@ -21,6 +21,7 @@ void AP_Mount_Servo::init()
|
|||||||
_pan_idx = SRV_Channel::k_mount2_pan;
|
_pan_idx = SRV_Channel::k_mount2_pan;
|
||||||
_open_idx = SRV_Channel::k_mount2_open;
|
_open_idx = SRV_Channel::k_mount2_open;
|
||||||
}
|
}
|
||||||
|
AP_Mount_Backend::init();
|
||||||
}
|
}
|
||||||
|
|
||||||
// update mount position - should be called periodically
|
// update mount position - should be called periodically
|
||||||
|
@ -33,7 +33,7 @@ void AP_Mount_Siyi::init()
|
|||||||
_initialised = true;
|
_initialised = true;
|
||||||
set_mode((enum MAV_MOUNT_MODE)_params.default_mode.get());
|
set_mode((enum MAV_MOUNT_MODE)_params.default_mode.get());
|
||||||
}
|
}
|
||||||
|
AP_Mount_Backend::init();
|
||||||
}
|
}
|
||||||
|
|
||||||
// update mount position - should be called periodically
|
// update mount position - should be called periodically
|
||||||
|
@ -16,6 +16,7 @@ void AP_Mount_SoloGimbal::init()
|
|||||||
{
|
{
|
||||||
_initialised = true;
|
_initialised = true;
|
||||||
set_mode((enum MAV_MOUNT_MODE)_params.default_mode.get());
|
set_mode((enum MAV_MOUNT_MODE)_params.default_mode.get());
|
||||||
|
AP_Mount_Backend::init();
|
||||||
}
|
}
|
||||||
|
|
||||||
void AP_Mount_SoloGimbal::update_fast()
|
void AP_Mount_SoloGimbal::update_fast()
|
||||||
|
Loading…
Reference in New Issue
Block a user