forked from Archive/PX4-Autopilot
manual_control_setpoint as msg
This commit is contained in:
parent
87df7c3243
commit
b3600e5ee6
|
@ -0,0 +1,44 @@
|
|||
|
||||
uint8 SWITCH_POS_NONE = 0 # switch is not mapped
|
||||
uint8 SWITCH_POS_ON = 1 # switch activated (value = 1)
|
||||
uint8 SWITCH_POS_MIDDLE = 2 # middle position (value = 0)
|
||||
uint8 SWITCH_POS_OFF = 3 # switch not activated (value = -1)
|
||||
uint64 timestamp
|
||||
|
||||
# Any of the channels may not be available and be set to NaN
|
||||
# to indicate that it does not contain valid data.
|
||||
# The variable names follow the definition of the
|
||||
# MANUAL_CONTROL mavlink message.
|
||||
# The default range is from -1 to 1 (mavlink message -1000 to 1000)
|
||||
# The range for the z variable is defined from 0 to 1. (The z field of
|
||||
# the MANUAL_CONTROL mavlink message is defined from -1000 to 1000)
|
||||
|
||||
float32 x # stick position in x direction -1..1
|
||||
# in general corresponds to forward/back motion or pitch of vehicle,
|
||||
# in general a positive value means forward or negative pitch and
|
||||
# a negative value means backward or positive pitch
|
||||
float32 y # stick position in y direction -1..1
|
||||
# in general corresponds to right/left motion or roll of vehicle,
|
||||
# in general a positive value means right or positive roll and
|
||||
# a negative value means left or negative roll
|
||||
float32 z # throttle stick position 0..1
|
||||
# in general corresponds to up/down motion or thrust of vehicle,
|
||||
# in general the value corresponds to the demanded throttle by the user,
|
||||
# if the input is used for setting the setpoint of a vertical position
|
||||
# controller any value > 0.5 means up and any value < 0.5 means down
|
||||
float32 r # yaw stick/twist positon, -1..1
|
||||
# in general corresponds to the righthand rotation around the vertical
|
||||
# (downwards) axis of the vehicle
|
||||
float32 flaps # flap position
|
||||
float32 aux1 # default function: camera yaw / azimuth
|
||||
float32 aux2 # default function: camera pitch / tilt
|
||||
float32 aux3 # default function: camera trigger
|
||||
float32 aux4 # default function: camera roll
|
||||
float32 aux5 # default function: payload drop
|
||||
|
||||
uint8 mode_switch # main mode 3 position switch (mandatory): _MANUAL_, ASSIST, AUTO
|
||||
uint8 return_switch # return to launch 2 position switch (mandatory): _NORMAL_, RTL
|
||||
uint8 posctl_switch # position control 2 position switch (optional): _ALTCTL_, POSCTL
|
||||
uint8 loiter_switch # loiter 2 position switch (optional): _MISSION_, LOITER
|
||||
uint8 acro_switch # acro 2 position switch (optional): _MANUAL_, ACRO
|
||||
uint8 offboard_switch # offboard 2 position switch (optional): _NORMAL_, OFFBOARD
|
|
@ -53,7 +53,6 @@
|
|||
#include <errno.h>
|
||||
#include <math.h>
|
||||
|
||||
#include <uORB/topics/manual_control_setpoint.h>
|
||||
#include <uORB/topics/actuator_controls.h>
|
||||
#include <uORB/topics/vehicle_rates_setpoint.h>
|
||||
#include <uORB/topics/vehicle_attitude.h>
|
||||
|
|
|
@ -61,7 +61,6 @@
|
|||
#include <poll.h>
|
||||
#include <drivers/drv_hrt.h>
|
||||
#include <arch/board/board.h>
|
||||
#include <uORB/topics/manual_control_setpoint.h>
|
||||
#include <uORB/topics/actuator_controls.h>
|
||||
#include <uORB/topics/vehicle_rates_setpoint.h>
|
||||
#include <uORB/topics/vehicle_attitude.h>
|
||||
|
|
|
@ -187,8 +187,8 @@ private:
|
|||
/**
|
||||
* Get switch position for specified function.
|
||||
*/
|
||||
switch_pos_t get_rc_sw3pos_position(uint8_t func, float on_th, bool on_inv, float mid_th, bool mid_inv);
|
||||
switch_pos_t get_rc_sw2pos_position(uint8_t func, float on_th, bool on_inv);
|
||||
uint8_t get_rc_sw3pos_position(uint8_t func, float on_th, bool on_inv, float mid_th, bool mid_inv);
|
||||
uint8_t get_rc_sw2pos_position(uint8_t func, float on_th, bool on_inv);
|
||||
|
||||
/**
|
||||
* Gather and publish RC input data.
|
||||
|
@ -1512,7 +1512,7 @@ Sensors::get_rc_value(uint8_t func, float min_value, float max_value)
|
|||
}
|
||||
}
|
||||
|
||||
switch_pos_t
|
||||
uint8_t
|
||||
Sensors::get_rc_sw3pos_position(uint8_t func, float on_th, bool on_inv, float mid_th, bool mid_inv)
|
||||
{
|
||||
if (_rc.function[func] >= 0) {
|
||||
|
@ -1533,7 +1533,7 @@ Sensors::get_rc_sw3pos_position(uint8_t func, float on_th, bool on_inv, float mi
|
|||
}
|
||||
}
|
||||
|
||||
switch_pos_t
|
||||
uint8_t
|
||||
Sensors::get_rc_sw2pos_position(uint8_t func, float on_th, bool on_inv)
|
||||
{
|
||||
if (_rc.function[func] >= 0) {
|
||||
|
|
|
@ -1,21 +1,20 @@
|
|||
/****************************************************************************
|
||||
*
|
||||
* Copyright (C) 2008-2012 PX4 Development Team. All rights reserved.
|
||||
* Author: @author Lorenz Meier <lm@inf.ethz.ch>
|
||||
* Copyright (C) 2013-2014 PX4 Development Team. All rights reserved.
|
||||
*
|
||||
* Redistribution and use in source and binary forms, with or without
|
||||
* modification, are permitted provided that the following conditions
|
||||
* are met:
|
||||
*
|
||||
* 1. Redistributions of source code must retain the above copyright
|
||||
* notice, this list of conditions and the following disclaimer.
|
||||
* notice, this list of conditions and the following disclaimer.
|
||||
* 2. Redistributions in binary form must reproduce the above copyright
|
||||
* notice, this list of conditions and the following disclaimer in
|
||||
* the documentation and/or other materials provided with the
|
||||
* distribution.
|
||||
* notice, this list of conditions and the following disclaimer in
|
||||
* the documentation and/or other materials provided with the
|
||||
* distribution.
|
||||
* 3. Neither the name PX4 nor the names of its contributors may be
|
||||
* used to endorse or promote products derived from this software
|
||||
* without specific prior written permission.
|
||||
* used to endorse or promote products derived from this software
|
||||
* without specific prior written permission.
|
||||
*
|
||||
* THIS SOFTWARE IS PROVIDED BY THE COPYRIGHT HOLDERS AND CONTRIBUTORS
|
||||
* "AS IS" AND ANY EXPRESS OR IMPLIED WARRANTIES, INCLUDING, BUT NOT
|
||||
|
@ -32,73 +31,44 @@
|
|||
*
|
||||
****************************************************************************/
|
||||
|
||||
/**
|
||||
* @file manual_control_setpoint.h
|
||||
* Definition of the manual_control_setpoint uORB topic.
|
||||
*/
|
||||
/* Auto-generated by genmsg_cpp from file /home/thomasgubler/src/catkin_ws/src/Firmware/msg/px4_msgs/manual_control_setpoint.msg */
|
||||
|
||||
#ifndef TOPIC_MANUAL_CONTROL_SETPOINT_H_
|
||||
#define TOPIC_MANUAL_CONTROL_SETPOINT_H_
|
||||
|
||||
#pragma once
|
||||
|
||||
#include <stdint.h>
|
||||
#include <platforms/px4_defines.h>
|
||||
#include "../uORB.h"
|
||||
|
||||
#define SWITCH_POS_NONE 0
|
||||
#define SWITCH_POS_ON 1
|
||||
#define SWITCH_POS_MIDDLE 2
|
||||
#define SWITCH_POS_OFF 3
|
||||
|
||||
/**
|
||||
* Switch position
|
||||
*/
|
||||
typedef enum {
|
||||
SWITCH_POS_NONE = 0, /**< switch is not mapped */
|
||||
SWITCH_POS_ON, /**< switch activated (value = 1) */
|
||||
SWITCH_POS_MIDDLE, /**< middle position (value = 0) */
|
||||
SWITCH_POS_OFF /**< switch not activated (value = -1) */
|
||||
} switch_pos_t;
|
||||
|
||||
/**
|
||||
* @addtogroup topics
|
||||
* @{
|
||||
*/
|
||||
|
||||
|
||||
struct manual_control_setpoint_s {
|
||||
uint64_t timestamp;
|
||||
|
||||
/**
|
||||
* Any of the channels may not be available and be set to NaN
|
||||
* to indicate that it does not contain valid data.
|
||||
* The variable names follow the definition of the
|
||||
* MANUAL_CONTROL mavlink message.
|
||||
* The default range is from -1 to 1 (mavlink message -1000 to 1000)
|
||||
* The range for the z variable is defined from 0 to 1. (The z field of
|
||||
* the MANUAL_CONTROL mavlink message is defined from -1000 to 1000)
|
||||
*/
|
||||
float x; /**< stick position in x direction -1..1
|
||||
in general corresponds to forward/back motion or pitch of vehicle,
|
||||
in general a positive value means forward or negative pitch and
|
||||
a negative value means backward or positive pitch */
|
||||
float y; /**< stick position in y direction -1..1
|
||||
in general corresponds to right/left motion or roll of vehicle,
|
||||
in general a positive value means right or positive roll and
|
||||
a negative value means left or negative roll */
|
||||
float z; /**< throttle stick position 0..1
|
||||
in general corresponds to up/down motion or thrust of vehicle,
|
||||
in general the value corresponds to the demanded throttle by the user,
|
||||
if the input is used for setting the setpoint of a vertical position
|
||||
controller any value > 0.5 means up and any value < 0.5 means down */
|
||||
float r; /**< yaw stick/twist positon, -1..1
|
||||
in general corresponds to the righthand rotation around the vertical
|
||||
(downwards) axis of the vehicle */
|
||||
float flaps; /**< flap position */
|
||||
float aux1; /**< default function: camera yaw / azimuth */
|
||||
float aux2; /**< default function: camera pitch / tilt */
|
||||
float aux3; /**< default function: camera trigger */
|
||||
float aux4; /**< default function: camera roll */
|
||||
float aux5; /**< default function: payload drop */
|
||||
|
||||
switch_pos_t mode_switch; /**< main mode 3 position switch (mandatory): _MANUAL_, ASSIST, AUTO */
|
||||
switch_pos_t return_switch; /**< return to launch 2 position switch (mandatory): _NORMAL_, RTL */
|
||||
switch_pos_t posctl_switch; /**< position control 2 position switch (optional): _ALTCTL_, POSCTL */
|
||||
switch_pos_t loiter_switch; /**< loiter 2 position switch (optional): _MISSION_, LOITER */
|
||||
switch_pos_t acro_switch; /**< acro 2 position switch (optional): _MANUAL_, ACRO */
|
||||
switch_pos_t offboard_switch; /**< offboard 2 position switch (optional): _NORMAL_, OFFBOARD */
|
||||
float x;
|
||||
float y;
|
||||
float z;
|
||||
float r;
|
||||
float flaps;
|
||||
float aux1;
|
||||
float aux2;
|
||||
float aux3;
|
||||
float aux4;
|
||||
float aux5;
|
||||
uint8_t mode_switch;
|
||||
uint8_t return_switch;
|
||||
uint8_t posctl_switch;
|
||||
uint8_t loiter_switch;
|
||||
uint8_t acro_switch;
|
||||
uint8_t offboard_switch;
|
||||
};
|
||||
|
||||
/**
|
||||
|
@ -107,5 +77,3 @@ struct manual_control_setpoint_s {
|
|||
|
||||
/* register this as object request broker structure */
|
||||
ORB_DECLARE(manual_control_setpoint);
|
||||
|
||||
#endif
|
||||
|
|
|
@ -56,6 +56,7 @@
|
|||
#include <uORB/uORB.h>
|
||||
#include <uORB/topics/rc_channels.h>
|
||||
#include <uORB/topics/vehicle_attitude_setpoint.h>
|
||||
#include <uORB/topics/manual_control_setpoint.h>
|
||||
#include <systemlib/err.h>
|
||||
#include <systemlib/param/param.h>
|
||||
|
||||
|
|
Loading…
Reference in New Issue