APM:Libraries
Classes | Public Member Functions | Private Types | Private Member Functions | Private Attributes | List of all members
AP_Mount_SToRM32_serial Class Reference

#include <AP_Mount_SToRM32_serial.h>

Inheritance diagram for AP_Mount_SToRM32_serial:
[legend]
Collaboration diagram for AP_Mount_SToRM32_serial:
[legend]

Classes

struct  cmd_set_angles_struct
 
union  SToRM32_reply
 
struct  SToRM32_reply_ack_struct
 
struct  SToRM32_reply_data_struct
 

Public Member Functions

 AP_Mount_SToRM32_serial (AP_Mount &frontend, AP_Mount::mount_state &state, uint8_t instance)
 
virtual void init (const AP_SerialManager &serial_manager)
 
virtual void update ()
 
virtual bool has_pan_control () const
 
virtual void set_mode (enum MAV_MOUNT_MODE mode)
 
virtual void status_msg (mavlink_channel_t chan)
 
- Public Member Functions inherited from AP_Mount_Backend
 AP_Mount_Backend (AP_Mount &frontend, AP_Mount::mount_state &state, uint8_t instance)
 
virtual ~AP_Mount_Backend (void)
 
virtual void update_fast ()
 
virtual void set_angle_targets (float roll, float tilt, float pan)
 
virtual void set_roi_target (const struct Location &target_loc)
 
virtual void control (int32_t pitch_or_lat, int32_t roll_or_lon, int32_t yaw_or_alt, MAV_MOUNT_MODE mount_mode)
 
virtual void configure_msg (mavlink_message_t *msg)
 
virtual void control_msg (mavlink_message_t *msg)
 
virtual void handle_gimbal_report (mavlink_channel_t chan, mavlink_message_t *msg)
 
virtual void handle_param_value (mavlink_message_t *msg)
 
virtual void send_gimbal_report (mavlink_channel_t chan)
 

Private Types

enum  ReplyType { ReplyType_UNKNOWN = 0, ReplyType_DATA, ReplyType_ACK }
 

Private Member Functions

void send_target_angles (float pitch_deg, float roll_deg, float yaw_deg)
 
void get_angles ()
 
void read_incoming ()
 
void parse_reply ()
 
uint8_t get_reply_size (ReplyType reply_type)
 
bool can_send (bool with_control)
 

Private Attributes

AP_HAL::UARTDriver_port
 
bool _initialised
 
uint32_t _last_send
 
uint8_t _reply_length
 
uint8_t _reply_counter
 
ReplyType _reply_type
 
union PACKED AP_Mount_SToRM32_serial::SToRM32_reply _buffer
 
Vector3l _current_angle
 

Additional Inherited Members

- Protected Member Functions inherited from AP_Mount_Backend
void update_targets_from_rc ()
 
int32_t angle_input (RC_Channel *rc, int16_t angle_min, int16_t angle_max)
 
float angle_input_rad (RC_Channel *rc, int16_t angle_min, int16_t angle_max)
 
void calc_angle_to_location (const struct Location &target, Vector3f &angles_to_target_rad, bool calc_tilt, bool calc_pan, bool relative_pan=true)
 
MAV_MOUNT_MODE get_mode (void) const
 
- Protected Attributes inherited from AP_Mount_Backend
AP_Mount_frontend
 
AP_Mount::mount_state_state
 
uint8_t _instance
 
Vector3f _angle_ef_target_rad
 

Detailed Description

Definition at line 18 of file AP_Mount_SToRM32_serial.h.

Member Enumeration Documentation

◆ ReplyType

Enumerator
ReplyType_UNKNOWN 
ReplyType_DATA 
ReplyType_ACK 

Definition at line 52 of file AP_Mount_SToRM32_serial.h.

Constructor & Destructor Documentation

◆ AP_Mount_SToRM32_serial()

AP_Mount_SToRM32_serial::AP_Mount_SToRM32_serial ( AP_Mount frontend,
AP_Mount::mount_state state,
uint8_t  instance 
)

Definition at line 9 of file AP_Mount_SToRM32_serial.cpp.

Member Function Documentation

◆ can_send()

bool AP_Mount_SToRM32_serial::can_send ( bool  with_control)
private

Definition at line 138 of file AP_Mount_SToRM32_serial.cpp.

Referenced by update().

Here is the call graph for this function:
Here is the caller graph for this function:

◆ get_angles()

void AP_Mount_SToRM32_serial::get_angles ( )
private

Definition at line 193 of file AP_Mount_SToRM32_serial.cpp.

Referenced by update().

Here is the call graph for this function:
Here is the caller graph for this function:

◆ get_reply_size()

uint8_t AP_Mount_SToRM32_serial::get_reply_size ( ReplyType  reply_type)
private

Definition at line 207 of file AP_Mount_SToRM32_serial.cpp.

Referenced by read_incoming(), and update().

Here is the caller graph for this function:

◆ has_pan_control()

bool AP_Mount_SToRM32_serial::has_pan_control ( ) const
virtual

Implements AP_Mount_Backend.

Definition at line 113 of file AP_Mount_SToRM32_serial.cpp.

◆ init()

void AP_Mount_SToRM32_serial::init ( const AP_SerialManager serial_manager)
virtual

Implements AP_Mount_Backend.

Definition at line 20 of file AP_Mount_SToRM32_serial.cpp.

Here is the call graph for this function:

◆ parse_reply()

void AP_Mount_SToRM32_serial::parse_reply ( )
private

Definition at line 261 of file AP_Mount_SToRM32_serial.cpp.

Referenced by read_incoming().

Here is the caller graph for this function:

◆ read_incoming()

void AP_Mount_SToRM32_serial::read_incoming ( )
private

Definition at line 221 of file AP_Mount_SToRM32_serial.cpp.

Referenced by update().

Here is the call graph for this function:
Here is the caller graph for this function:

◆ send_target_angles()

void AP_Mount_SToRM32_serial::send_target_angles ( float  pitch_deg,
float  roll_deg,
float  yaw_deg 
)
private

Definition at line 148 of file AP_Mount_SToRM32_serial.cpp.

Referenced by update().

Here is the call graph for this function:
Here is the caller graph for this function:

◆ set_mode()

void AP_Mount_SToRM32_serial::set_mode ( enum MAV_MOUNT_MODE  mode)
virtual

Implements AP_Mount_Backend.

Definition at line 120 of file AP_Mount_SToRM32_serial.cpp.

Referenced by init().

Here is the caller graph for this function:

◆ status_msg()

void AP_Mount_SToRM32_serial::status_msg ( mavlink_channel_t  chan)
virtual

Reimplemented from AP_Mount_Backend.

Definition at line 132 of file AP_Mount_SToRM32_serial.cpp.

◆ update()

void AP_Mount_SToRM32_serial::update ( void  )
virtual

Implements AP_Mount_Backend.

Definition at line 31 of file AP_Mount_SToRM32_serial.cpp.

Here is the call graph for this function:

Member Data Documentation

◆ _buffer

union PACKED AP_Mount_SToRM32_serial::SToRM32_reply AP_Mount_SToRM32_serial::_buffer
private

Referenced by parse_reply(), and read_incoming().

◆ _current_angle

Vector3l AP_Mount_SToRM32_serial::_current_angle
private

Definition at line 150 of file AP_Mount_SToRM32_serial.h.

Referenced by parse_reply(), and status_msg().

◆ _initialised

bool AP_Mount_SToRM32_serial::_initialised
private

Definition at line 135 of file AP_Mount_SToRM32_serial.h.

Referenced by get_angles(), init(), send_target_angles(), set_mode(), and update().

◆ _last_send

uint32_t AP_Mount_SToRM32_serial::_last_send
private

Definition at line 136 of file AP_Mount_SToRM32_serial.h.

Referenced by send_target_angles(), and update().

◆ _port

AP_HAL::UARTDriver* AP_Mount_SToRM32_serial::_port
private

◆ _reply_counter

uint8_t AP_Mount_SToRM32_serial::_reply_counter
private

Definition at line 139 of file AP_Mount_SToRM32_serial.h.

Referenced by read_incoming(), and update().

◆ _reply_length

uint8_t AP_Mount_SToRM32_serial::_reply_length
private

Definition at line 138 of file AP_Mount_SToRM32_serial.h.

Referenced by read_incoming(), and update().

◆ _reply_type

ReplyType AP_Mount_SToRM32_serial::_reply_type
private

Definition at line 140 of file AP_Mount_SToRM32_serial.h.

Referenced by can_send(), parse_reply(), read_incoming(), and update().


The documentation for this class was generated from the following files: