Browse Source

Added missing enum definitions

Fixed float equality checks
sbg
Anton Matosov 10 years ago
parent
commit
076180a983
  1. 5
      src/drivers/servo_gimbal/gimbal.cpp
  2. 27
      src/modules/uORB/topics/vehicle_command.h

5
src/drivers/servo_gimbal/gimbal.cpp

@ -73,6 +73,7 @@ @@ -73,6 +73,7 @@
#include <uORB/topics/vehicle_attitude.h>
#include <board_config.h>
#include <mathlib/math/test/test.hpp>
/* Configuration Constants */
@ -312,7 +313,7 @@ Gimbal::cycle() @@ -312,7 +313,7 @@ Gimbal::cycle()
//debug("cmd: %d, param1: %8.4f param2: %8.4f", (double)cmd.command, (double)cmd.param1, (double)cmd.param2);
if (cmd.command == VEHICLE_CMD_DO_MOUNT_CONTROL && cmd.param7 == 2) {
if (cmd.command == VEHICLE_CMD_DO_MOUNT_CONTROL && equal(cmd.param7, VEHICLE_MOUNT_MODE_MAVLINK_TARGETING)) {
/* Convert to range -1 ... 1, which corresponds to -180deg ... 180deg */
roll += 1.0f / M_PI_F * M_DEG_TO_RAD_F * cmd.param1;
@ -323,7 +324,7 @@ Gimbal::cycle() @@ -323,7 +324,7 @@ Gimbal::cycle()
}
// XXX change this to the real quaternion command
if (cmd.command == VEHICLE_CMD_DO_MOUNT_CONTROL_QUAT && cmd.param7 == 2) {
if (cmd.command == VEHICLE_CMD_DO_MOUNT_CONTROL_QUAT && equal(cmd.param7, VEHICLE_MOUNT_MODE_MAVLINK_TARGETING)) {
/* Convert to range -1 ... 1, which corresponds to -180deg ... 180deg */
roll += 1.0f / M_PI_F * M_DEG_TO_RAD_F * cmd.param1;

27
src/modules/uORB/topics/vehicle_command.h

@ -85,6 +85,15 @@ enum VEHICLE_CMD { @@ -85,6 +85,15 @@ enum VEHICLE_CMD {
VEHICLE_CMD_DO_REPEAT_SERVO = 184, /* Cycle a between its nominal setting and a desired PWM for a desired number of cycles with a desired period. |Servo number| PWM (microseconds, 1000 to 2000 typical)| Cycle count| Cycle time (seconds)| Empty| Empty| Empty| */
VEHICLE_CMD_DO_FLIGHTTERMINATION=185, /* Terminate flight immediately |Flight termination activated if > 0.5| Empty| Empty| Empty| Empty| Empty| Empty| */
VEHICLE_CMD_DO_CONTROL_VIDEO = 200, /* Control onboard camera system. |Camera ID (-1 for all)| Transmission: 0: disabled, 1: enabled compressed, 2: enabled raw| Transmission mode: 0: video stream, >0: single images every n seconds (decimal)| Recording: 0: disabled, 1: enabled compressed, 2: enabled raw| Empty| Empty| Empty| */
VEHICLE_CMD_DO_MOUNT_CONFIGURE=204, /* Mission command to configure a camera or antenna mount |Mount operation mode (see MAV_MOUNT_MODE enum)| stabilize roll? (1 = yes, 0 = no)| stabilize pitch? (1 = yes, 0 = no)| stabilize yaw? (1 = yes, 0 = no)| Empty| Empty| Empty| */
VEHICLE_CMD_DO_MOUNT_CONTROL=205, /* Mission command to control a camera or antenna mount |pitch or lat in degrees, depending on mount mode.| roll or lon in degrees depending on mount mode| yaw or alt (in meters) depending on mount mode| reserved| reserved| reserved| MAV_MOUNT_MODE enum value| */
VEHICLE_CMD_DO_SET_CAM_TRIGG_DIST=206, /* Mission command to set CAM_TRIGG_DIST for this flight |Camera trigger distance (meters)| Empty| Empty| Empty| Empty| Empty| Empty| */
VEHICLE_CMD_DO_FENCE_ENABLE=207, /* Mission command to enable the geofence |enable? (0=disable, 1=enable)| Empty| Empty| Empty| Empty| Empty| Empty| */
VEHICLE_CMD_DO_PARACHUTE=208, /* Mission command to trigger a parachute |action (0=disable, 1=enable, 2=release, for some systems see PARACHUTE_ACTION enum, not in general message set.)| Empty| Empty| Empty| Empty| Empty| Empty| */
VEHICLE_CMD_DO_INVERTED_FLIGHT=210, /* Change to/from inverted flight |inverted (0=normal, 1=inverted)| Empty| Empty| Empty| Empty| Empty| Empty| */
VEHICLE_CMD_DO_MOUNT_CONTROL_QUAT=220, /* Mission command to control a camera or antenna mount, using a quaternion as reference. |q1 - quaternion param #1, w (1 in null-rotation)| q2 - quaternion param #2, x (0 in null-rotation)| q3 - quaternion param #3, y (0 in null-rotation)| q4 - quaternion param #4, z (0 in null-rotation)| Empty| Empty| Empty| */
VEHICLE_CMD_DO_GUIDED_MASTER=221, /* set id of master controller |System ID| Component ID| Empty| Empty| Empty| Empty| Empty| */
VEHICLE_CMD_DO_GUIDED_LIMITS=222, /* set limits for external control |timeout - maximum time (in seconds) that external controller will be allowed to control vehicle. 0 means no timeout| absolute altitude min (in meters, AMSL) - if vehicle moves below this alt, the command will be aborted and the mission will continue. 0 means no lower altitude limit| absolute altitude max (in meters)- if vehicle moves above this alt, the command will be aborted and the mission will continue. 0 means no upper altitude limit| horizontal move limit (in meters, AMSL) - if vehicle moves more than this distance from it's location at the moment the command was executed, the command will be aborted and the mission will continue. 0 means no horizontal altitude limit| Empty| Empty| Empty| */
VEHICLE_CMD_DO_LAST = 240, /* NOP - This command is only used to mark the upper limit of the DO commands in the enumeration |Empty| Empty| Empty| Empty| Empty| Empty| Empty| */
VEHICLE_CMD_PREFLIGHT_CALIBRATION = 241, /* Trigger calibration. This command will be only accepted if in pre-flight mode. |Gyro calibration: 0: no, 1: yes| Magnetometer calibration: 0: no, 1: yes| Ground pressure: 0: no, 1: yes| Radio calibration: 0: no, 1: yes| Accelerometer calibration: 0: no, 1: yes| Empty| Empty| */
VEHICLE_CMD_PREFLIGHT_SET_SENSOR_OFFSETS = 242, /* Set sensor offsets. This command will be only accepted if in pre-flight mode. |Sensor to adjust the offsets for: 0: gyros, 1: accelerometer, 2: magnetometer, 3: barometer, 4: optical flow| X axis offset (or generic dimension 1), in the sensor's raw units| Y axis offset (or generic dimension 2), in the sensor's raw units| Z axis offset (or generic dimension 3), in the sensor's raw units| Generic dimension 4, in the sensor's raw units| Generic dimension 5, in the sensor's raw units| Generic dimension 6, in the sensor's raw units| */
@ -101,7 +110,7 @@ enum VEHICLE_CMD { @@ -101,7 +110,7 @@ enum VEHICLE_CMD {
/**
* Commands for commander app.
*
* Should contain all of MAVLink's VEHICLE_CMD_RESULT values
* Should contain all of MAVLink's MAV_CMD_RESULT values
* but can contain additional ones.
*/
enum VEHICLE_CMD_RESULT {
@ -113,6 +122,22 @@ enum VEHICLE_CMD_RESULT { @@ -113,6 +122,22 @@ enum VEHICLE_CMD_RESULT {
VEHICLE_CMD_RESULT_ENUM_END = 5, /* | */
};
/**
* Commands for gimbal app.
*
* Should contain all of MAVLink's MAV_MOUNT_MODE values
* but can contain additional ones.
*/
typedef enum VEHICLE_MOUNT_MODE
{
VEHICLE_MOUNT_MODE_RETRACT=0, /* Load and keep safe position (Roll,Pitch,Yaw) from permant memory and stop stabilization | */
VEHICLE_MOUNT_MODE_NEUTRAL=1, /* Load and keep neutral position (Roll,Pitch,Yaw) from permanent memory. | */
VEHICLE_MOUNT_MODE_MAVLINK_TARGETING=2, /* Load neutral position and start MAVLink Roll,Pitch,Yaw control with stabilization | */
VEHICLE_MOUNT_MODE_RC_TARGETING=3, /* Load neutral position and start RC Roll,Pitch,Yaw control with stabilization | */
VEHICLE_MOUNT_MODE_GPS_POINT=4, /* Load neutral position and start to point to Lat,Lon,Alt | */
VEHICLE_MOUNT_MODE_ENUM_END=5, /* | */
} VEHICLE_MOUNT_MODE;
/**
* @addtogroup topics
* @{

Loading…
Cancel
Save