44 #include <px4_platform_common/posix.h> 45 #include <px4_platform_common/defines.h> 52 InputRC::InputRC(
bool do_stabilization,
int aux_channel_roll,
int aux_channel_pitch,
int aux_channel_yaw)
53 : _do_stabilization(do_stabilization)
81 *control_data =
nullptr;
83 px4_pollfd_struct_t polls[1];
85 polls[0].events = POLLIN;
87 int ret =
px4_poll(polls, 1, timeout_ms);
96 if (polls[0].revents & POLLIN) {
113 float new_aux_values[3];
115 for (
int i = 0; i < 3; ++i) {
121 bool major_movement =
false;
124 for (
int i = 0; i < 3; ++i) {
126 major_movement =
true;
130 if (already_active || major_movement ||
_first_time) {
134 for (
int i = 0; i < 3; ++i) {
155 return manual_control_setpoint.
aux1;
158 return manual_control_setpoint.
aux2;
161 return manual_control_setpoint.
aux3;
164 return manual_control_setpoint.
aux4;
167 return manual_control_setpoint.
aux5;
170 return manual_control_setpoint.
aux6;
int orb_copy(const struct orb_metadata *meta, int handle, void *buffer)
int orb_subscribe(const struct orb_metadata *meta)
bool gimbal_shutter_retract
whether to lock the gimbal (only in RC output mode)
#define ORB_ID(_name)
Generates a pointer to the uORB metadata structure for a given topic.
int orb_unsubscribe(int handle)
Vector< float, 6 > f(float t, const Matrix< float, 6, 1 > &, const Matrix< float, 3, 1 > &)
float angles[3]
attitude angles (roll, pitch, yaw) in rad, [-pi, +pi] if is_speed[i] == false
This defines the common API between an input and an output of the vmount driver.
bool is_speed[3]
if true, the angle is the angular speed in rad/s
control the roll, pitch & yaw angle directly
struct vmount::ControlData::TypeData::TypeAngle angle
bool stabilize_axis[3]
whether the vmount driver should stabilize an axis (if the output supports it, this can also be done ...
union vmount::ControlData::TypeData type_data