31 target_address(
"127.0.0.1"),
36 reporting_period_ms(10),
37 seen_heartbeat(false),
38 seen_gimbal_control(false),
116 Vector3f(sinf(elevAngle)*tanf(rollAngle), 1, -cosf(elevAngle)*tanf(rollAngle)),
117 Vector3f(-sinf(elevAngle)/cosf(rollAngle), 0, cosf(elevAngle)/cosf(rollAngle)));
118 Vector3f gimbalJointRates = matrix * relativeGimbalRate;
121 gimbalJointRates.
x =
constrain_float(gimbalJointRates.
x, lowerRatelimit.
x, upperRatelimit.
x);
122 gimbalJointRates.
y =
constrain_float(gimbalJointRates.
y, lowerRatelimit.
y, upperRatelimit.
y);
123 gimbalJointRates.
z =
constrain_float(gimbalJointRates.
z, lowerRatelimit.
z, upperRatelimit.
z);
139 matrix =
Matrix3f(
Vector3f(cosf(elevAngle), 0, -cosf(rollAngle)*sinf(elevAngle)),
141 Vector3f(sinf(elevAngle), 0, cosf(elevAngle)*cosf(rollAngle)));
142 relativeGimbalRate = matrix * gimbalJointRates;
169 Vector3f copter_accel_earth = vehicle_dcm * vehicle_accel_body;
201 while ((ret=
mav_socket.recv(buf,
sizeof(buf), 0)) > 0) {
202 for (uint8_t i=0; i<ret; i++) {
203 mavlink_message_t msg;
207 &msg, &status) == MAVLINK_FRAMING_OK) {
209 case MAVLINK_MSG_ID_HEARTBEAT: {
218 case MAVLINK_MSG_ID_GIMBAL_CONTROL: {
219 mavlink_gimbal_control_t pkt;
220 mavlink_msg_gimbal_control_decode(&msg, &pkt);
223 pkt.demanded_rate_z);
238 mavlink_message_t msg;
242 mavlink_heartbeat_t heartbeat;
243 heartbeat.type = MAV_TYPE_GIMBAL;
244 heartbeat.autopilot = MAV_AUTOPILOT_ARDUPILOTMEGA;
245 heartbeat.base_mode = 0;
246 heartbeat.system_status = 0;
247 heartbeat.mavlink_version = 0;
248 heartbeat.custom_mode = 0;
254 mavlink_status_t *chan0_status = mavlink_get_channel_status(MAVLINK_COMM_0);
255 uint8_t saved_seq = chan0_status->current_tx_seq;
256 chan0_status->current_tx_seq =
mavlink.seq;
260 chan0_status->current_tx_seq = saved_seq;
271 mavlink_gimbal_report_t gimbal_report;
276 gimbal_report.delta_time = delta_time;
287 mavlink_status_t *chan0_status = mavlink_get_channel_status(MAVLINK_COMM_0);
288 uint8_t saved_seq = chan0_status->current_tx_seq;
289 chan0_status->current_tx_seq =
mavlink.seq;
292 &msg, &gimbal_report);
293 chan0_status->current_tx_seq = saved_seq;
296 len = mavlink_msg_to_send_buffer(msgbuf, &msg);
int printf(const char *fmt,...)
Vector3f upper_joint_limits
Vector3< float > Vector3f
const struct sitl_fdm & fdm
uint8_t vehicle_system_id
Vector3f lower_joint_limits
Matrix3< float > Matrix3f
Vector3f gimbal_angular_rate
const uint16_t target_port
Matrix3< T > transposed(void) const
const AP_HAL::HAL & hal
-*- tab-width: 4; Mode: C++; c-basic-offset: 4; indent-tabs-mode: nil -*-
Vector3< T > to_euler312() const
Gimbal(const struct sitl_fdm &_fdm)
void rotation_matrix(Matrix3f &m) const
Vector3f supplied_gyro_bias
const float travelLimitGain
float constrain_float(const float amt, const float low, const float high)
static constexpr float radians(float deg)
uint32_t last_heartbeat_ms
const char * target_address
void rotate(const Vector3< T > &g)
struct SITL::Gimbal::@203 mavlink
const float reporting_period_ms
Vector3f demanded_angular_rate
uint8_t vehicle_component_id