4 #include <GCS_MAVLink/include/mavlink/v2.0/checksum.h> 16 _reply_type(ReplyType_UNKNOWN)
41 bool resend_now =
false;
46 case MAV_MOUNT_MODE_RETRACT:
56 case MAV_MOUNT_MODE_NEUTRAL:
66 case MAV_MOUNT_MODE_MAVLINK_TARGETING:
71 case MAV_MOUNT_MODE_RC_TARGETING:
78 case MAV_MOUNT_MODE_GPS_POINT:
139 uint16_t required_tx = 1;
168 if ((
size_t)
_port->
txspace() <
sizeof(cmd_set_angles_data)) {
173 pitch_deg = -pitch_deg;
177 cmd_set_angles_data.
pitch = pitch_deg;
178 cmd_set_angles_data.
roll = roll_deg;
179 cmd_set_angles_data.
yaw = yaw_deg;
181 uint8_t* buf = (uint8_t*)&cmd_set_angles_data;
183 cmd_set_angles_data.
crc = crc_calculate(&buf[1],
sizeof(cmd_set_angles_data)-3);
185 for (uint8_t i = 0; i !=
sizeof(cmd_set_angles_data) ; i++) {
208 switch (reply_type) {
231 for (int16_t i = 0; i < numc; i++) {
278 crc = crc_calculate(&
_buffer[1],
SToRM32_reply_ack_struct ack
static AP_SerialManager serial_manager
virtual void init(const AP_SerialManager &serial_manager)
Vector3f _angle_ef_target_rad
void update_targets_from_rc()
union PACKED AP_Mount_SToRM32_serial::SToRM32_reply _buffer
uint8_t get_reply_size(ReplyType reply_type)
bool can_send(bool with_control)
virtual uint32_t txspace()=0
AP_Mount::mount_state & _state
void send_target_angles(float pitch_deg, float roll_deg, float yaw_deg)
virtual void status_msg(mavlink_channel_t chan)
void calc_angle_to_location(const struct Location &target, Vector3f &angles_to_target_rad, bool calc_tilt, bool calc_pan, bool relative_pan=true)
virtual size_t write(uint8_t)=0
struct Location _roi_target
AP_Vector3f _retract_angles
Receiving valid messages and 2D lock.
virtual bool has_pan_control() const
AP_Vector3f _neutral_angles
virtual uint32_t available()=0
AP_HAL::AnalogSource * chan
DEFINE_BYTE_ARRAY_METHODS SToRM32_reply_data_struct data
AP_Mount_SToRM32_serial(AP_Mount &frontend, AP_Mount::mount_state &state, uint8_t instance)
#define AP_MOUNT_STORM32_SERIAL_RESEND_MS
virtual void set_mode(enum MAV_MOUNT_MODE mode)
const AP_HAL::HAL & hal
-*- tab-width: 4; Mode: C++; c-basic-offset: 4; indent-tabs-mode: nil -*-
AP_HAL::UARTDriver * _port
MAV_MOUNT_MODE get_mode(void) const
AP_HAL::UARTDriver * find_serial(enum SerialProtocol protocol, uint8_t instance) const