mirror of
https://github.com/ArduPilot/ardupilot
synced 2025-01-22 08:38:36 -04:00
AP_Mount_Alexmos: use struct for CMD_CONTROL command
new struct created in header and used in control_axis function
This commit is contained in:
parent
81d60af4a8
commit
46e92f99fe
@ -123,24 +123,15 @@ void AP_Mount_Alexmos::control_axis(const Vector3f& angle, bool target_in_degree
|
||||
if (!target_in_degrees) {
|
||||
target_deg *= RAD_TO_DEG;
|
||||
}
|
||||
|
||||
uint8_t mode = AP_MOUNT_ALEXMOS_MODE_ANGLE;
|
||||
int16_t speed_roll = DEGREE_PER_SEC_TO_VALUE(AP_MOUNT_ALEXMOS_SPEED);
|
||||
int16_t angle_roll = DEGREE_TO_VALUE(target_deg.x);
|
||||
int16_t speed_pitch = DEGREE_PER_SEC_TO_VALUE(AP_MOUNT_ALEXMOS_SPEED);
|
||||
int16_t angle_pitch = DEGREE_TO_VALUE(target_deg.y);
|
||||
int16_t speed_yaw = DEGREE_PER_SEC_TO_VALUE(AP_MOUNT_ALEXMOS_SPEED);
|
||||
int16_t angle_yaw = DEGREE_TO_VALUE(target_deg.z);
|
||||
uint8_t data[13] = {
|
||||
(uint8_t)mode,
|
||||
(uint8_t)speed_roll, (uint8_t)(speed_roll >> 8),
|
||||
(uint8_t)angle_roll, (uint8_t)(angle_roll >> 8 ),
|
||||
(uint8_t)speed_pitch, (uint8_t)(speed_pitch >> 8),
|
||||
(uint8_t)angle_pitch, (uint8_t)(angle_pitch >> 8),
|
||||
(uint8_t)speed_yaw, (uint8_t)(speed_yaw >> 8),
|
||||
(uint8_t)angle_yaw, (uint8_t)(angle_yaw >> 8)
|
||||
};
|
||||
send_command (CMD_CONTROL, data , 13);
|
||||
alexmos_parameters outgoing_buffer;
|
||||
outgoing_buffer.angle_speed.mode = AP_MOUNT_ALEXMOS_MODE_ANGLE;
|
||||
outgoing_buffer.angle_speed.speed_roll = DEGREE_PER_SEC_TO_VALUE(AP_MOUNT_ALEXMOS_SPEED);
|
||||
outgoing_buffer.angle_speed.angle_roll = DEGREE_TO_VALUE(target_deg.x);
|
||||
outgoing_buffer.angle_speed.speed_pitch = DEGREE_PER_SEC_TO_VALUE(AP_MOUNT_ALEXMOS_SPEED);
|
||||
outgoing_buffer.angle_speed.angle_pitch = DEGREE_TO_VALUE(target_deg.y);
|
||||
outgoing_buffer.angle_speed.speed_yaw = DEGREE_PER_SEC_TO_VALUE(AP_MOUNT_ALEXMOS_SPEED);
|
||||
outgoing_buffer.angle_speed.angle_yaw = DEGREE_TO_VALUE(target_deg.z);
|
||||
send_command (CMD_CONTROL, outgoing_buffer.bytes , sizeof (alexmos_angles_speed));
|
||||
}
|
||||
|
||||
/*
|
||||
|
@ -157,6 +157,17 @@ private:
|
||||
int16_t rc_speed_yaw;
|
||||
};
|
||||
|
||||
// CMD_CONTROL
|
||||
struct PACKED alexmos_angles_speed {
|
||||
int8_t mode;
|
||||
int16_t speed_roll;
|
||||
int16_t angle_roll;
|
||||
int16_t speed_pitch;
|
||||
int16_t angle_pitch;
|
||||
int16_t speed_yaw;
|
||||
int16_t angle_yaw;
|
||||
};
|
||||
|
||||
// CMD_READ_PARAMS
|
||||
struct PACKED alexmos_params {
|
||||
uint8_t profile_id;
|
||||
@ -272,10 +283,11 @@ private:
|
||||
uint8_t cur_profile_id;
|
||||
|
||||
};
|
||||
union PACKED {
|
||||
union PACKED alexmos_parameters {
|
||||
alexmos_version version;
|
||||
alexmos_angles angles;
|
||||
alexmos_params params;
|
||||
alexmos_angles_speed angle_speed;
|
||||
uint8_t bytes[];
|
||||
} _buffer,_current_parameters;
|
||||
|
||||
|
Loading…
Reference in New Issue
Block a user