30 __mavlink_mount_configure_t packet;
31 mavlink_msg_mount_configure_decode(msg, &packet);
33 set_mode((MAV_MOUNT_MODE)packet.mount_mode);
39 __mavlink_mount_control_t packet;
40 mavlink_msg_mount_control_decode(msg, &packet);
42 control((int32_t)packet.input_a, (int32_t)packet.input_b, (int32_t)packet.input_c,
_state.
_mode);
51 case MAV_MOUNT_MODE_RETRACT:
52 case MAV_MOUNT_MODE_NEUTRAL:
57 case MAV_MOUNT_MODE_MAVLINK_TARGETING:
62 case MAV_MOUNT_MODE_RC_TARGETING:
67 case MAV_MOUNT_MODE_GPS_POINT:
69 memset(&target_location, 0,
sizeof(target_location));
70 target_location.
lat = pitch_or_lat;
71 target_location.
lng = roll_or_lon;
72 target_location.
alt = yaw_or_alt;
86 #define rc_ch(i) RC_Channels::rc_channel(i-1) 95 if (roll_rc_in &&
rc_ch(roll_rc_in)) {
99 if (tilt_rc_in && (
rc_ch(tilt_rc_in))) {
103 if (pan_rc_in && (
rc_ch(pan_rc_in))) {
109 if (roll_rc_in && (
rc_ch(roll_rc_in))) {
112 if (tilt_rc_in && (
rc_ch(tilt_rc_in))) {
115 if (pan_rc_in && (
rc_ch(pan_rc_in))) {
140 float target_distance = 100.0f*
norm(GPS_vector_x, GPS_vector_y);
143 angles_to_target_rad.
zero();
147 angles_to_target_rad.
y = atan2f(GPS_vector_z, target_distance);
153 angles_to_target_rad.
z = atan2f(GPS_vector_x, GPS_vector_y);
float norm(const T first, const U second, const Params... parameters)
const AP_HAL::HAL & hal
-*- tab-width: 4; Mode: C++; c-basic-offset: 4; indent-tabs-mode: nil -*-
Vector3f _angle_ef_target_rad
void set_mode(enum MAV_MOUNT_MODE mode)
virtual void control(int32_t pitch_or_lat, int32_t roll_or_lon, int32_t yaw_or_alt, MAV_MOUNT_MODE mount_mode)
void update_targets_from_rc()
int16_t get_radio_in() const
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)
enum MAV_MOUNT_MODE get_mode() const
virtual void control_msg(mavlink_message_t *msg)
AP_Mount::mount_state & _state
virtual void set_mode(enum MAV_MOUNT_MODE mode)=0
int32_t lat
param 3 - Latitude * 10**7
virtual void set_angle_targets(float roll, float tilt, float pan)
float wrap_PI(const T radian)
int32_t alt
param 2 - Altitude in centimeters (meters * 100) see LOCATION_ALT_MAX_M
Object managing one RC channel.
void calc_angle_to_location(const struct Location &target, Vector3f &angles_to_target_rad, bool calc_tilt, bool calc_pan, bool relative_pan=true)
struct Location _roi_target
virtual void configure_msg(mavlink_message_t *msg)
Location_Option_Flags flags
options bitmask (1<<0 = relative altitude)
virtual void set_roi_target(const struct Location &target_loc)
float constrain_float(const float amt, const float low, const float high)
int32_t lng
param 4 - Longitude * 10**7
const AP_AHRS_TYPE & _ahrs
static constexpr float radians(float deg)
bool get_reverse(void) const
int16_t get_radio_min() const
int16_t get_radio_max() const
const struct Location & _current_loc