Mission: cmd field types to match mavlink commands

Split Set-Servo and Repeat-Servo command structures
Split Set-Relay and Repeat-Relay command structures
This commit is contained in:
Randy Mackay 2014-03-19 11:13:04 +09:00
parent 1f74736804
commit c520cb789c
2 changed files with 48 additions and 31 deletions

View File

@ -519,9 +519,9 @@ bool AP_Mission::mavlink_to_mission_cmd(const mavlink_mission_item_t& packet, AP
break;
case MAV_CMD_DO_REPEAT_RELAY: // MAV ID: 182
cmd.content.relay.num = packet.param1; // relay number
cmd.content.relay.repeat_count = packet.param2; // count
cmd.content.relay.time_ms = packet.param3*1000; // time converted from seconds to milliseconds
cmd.content.repeat_relay.num = packet.param1; // relay number
cmd.content.repeat_relay.repeat_count = packet.param2; // count
cmd.content.repeat_relay.cycle_time = packet.param3; // time converted from seconds to milliseconds
break;
case MAV_CMD_DO_SET_SERVO: // MAV ID: 183
@ -530,10 +530,10 @@ bool AP_Mission::mavlink_to_mission_cmd(const mavlink_mission_item_t& packet, AP
break;
case MAV_CMD_DO_REPEAT_SERVO: // MAV ID: 184
cmd.content.servo.channel = packet.param1; // channel
cmd.content.servo.pwm = packet.param2; // PWM
cmd.content.servo.repeat_count = packet.param3; // count
cmd.content.servo.time_ms = packet.param4*1000; // time in seconds converted to milliseconds
cmd.content.repeat_servo.channel = packet.param1; // channel
cmd.content.repeat_servo.pwm = packet.param2; // PWM
cmd.content.repeat_servo.repeat_count = packet.param3; // count
cmd.content.repeat_servo.cycle_time = packet.param4; // time in seconds
break;
case MAV_CMD_DO_SET_ROI: // MAV ID: 201
@ -733,9 +733,9 @@ bool AP_Mission::mission_cmd_to_mavlink(const AP_Mission::Mission_Command& cmd,
break;
case MAV_CMD_DO_REPEAT_RELAY: // MAV ID: 182
packet.param1 = cmd.content.relay.num; // relay number
packet.param2 = cmd.content.relay.repeat_count; // count
packet.param3 = cmd.content.relay.time_ms*0.001f; // time converted from milliseconds to seconds
packet.param1 = cmd.content.repeat_relay.num; // relay number
packet.param2 = cmd.content.repeat_relay.repeat_count; // count
packet.param3 = cmd.content.repeat_relay.cycle_time; // time in seconds
break;
case MAV_CMD_DO_SET_SERVO: // MAV ID: 183
@ -744,10 +744,10 @@ bool AP_Mission::mission_cmd_to_mavlink(const AP_Mission::Mission_Command& cmd,
break;
case MAV_CMD_DO_REPEAT_SERVO: // MAV ID: 184
packet.param1 = cmd.content.servo.channel; // channel
packet.param2 = cmd.content.servo.pwm; // PWM
packet.param3 = cmd.content.servo.repeat_count; // count
packet.param4 = cmd.content.servo.time_ms*0.001f; // time in milliseconds converted to seconds
packet.param1 = cmd.content.repeat_servo.channel; // channel
packet.param2 = cmd.content.repeat_servo.pwm; // PWM
packet.param3 = cmd.content.repeat_servo.repeat_count; // count
packet.param4 = cmd.content.repeat_servo.cycle_time; // time in milliseconds converted to seconds
break;
case MAV_CMD_DO_SET_ROI: // MAV ID: 201

View File

@ -49,48 +49,59 @@ public:
// condition delay command structure
struct PACKED Conditional_Delay_Command {
uint16_t seconds; // period of delay in seconds
float seconds; // period of delay in seconds
};
// condition delay command structure
struct PACKED Conditional_Distance_Command {
int32_t meters; // distance from next waypoint in meters
float meters; // distance from next waypoint in meters
};
// condition yaw command structure
struct PACKED Yaw_Command {
int16_t angle_deg; // target angle in degrees (0=north, 90=east)
int16_t turn_rate_dps; // turn rate in degrees / second (0=use default)
int8_t direction; // -1 = ccw, +1 = cw
uint8_t relative_angle;// 0 = absolute angle, 1 = relative angle
float angle_deg; // target angle in degrees (0=north, 90=east)
float turn_rate_dps; // turn rate in degrees / second (0=use default)
int8_t direction; // -1 = ccw, +1 = cw
uint8_t relative_angle; // 0 = absolute angle, 1 = relative angle
};
// change speed command structure
struct PACKED Change_Speed_Command {
uint8_t speed_type; // 0=airspeed, 1=ground speed
float target_ms; // target speed in m/s
uint8_t throttle_pct; // throttle as a percentage (i.e. 0 ~ 100)
float target_ms; // target speed in m/s, -1 means no change
float throttle_pct; // throttle as a percentage (i.e. 0 ~ 100), -1 means no change
};
// set relay and repeat relay command structure
// set relay command structure
struct PACKED Set_Relay_Command {
uint8_t num; // relay number from 1 to 4
uint8_t state; // on = 3.3V or 5V (depending upon board), off = 0V. only used for do-set-relay, not for do-repeat-relay
int16_t repeat_count; // number of times to trigger the relay
uint32_t time_ms; // cycle time in milliseconds (the time between peaks or the time the relay is on and off for each cycle?)
};
// set servo and repeat servo command structure
// repeat relay command structure
struct PACKED Repeat_Relay_Command {
uint8_t num; // relay number from 1 to 4
int16_t repeat_count; // number of times to trigger the relay
float cycle_time; // cycle time in seconds (the time between peaks or the time the relay is on and off for each cycle?)
};
// set servo command structure
struct PACKED Set_Servo_Command {
uint8_t channel; // Note: p1 holds servo channel
uint8_t channel; // servo channel
uint16_t pwm; // pwm value for servo
};
// repeat servo command structure
struct PACKED Repeat_Servo_Command {
uint8_t channel; // servo channel
uint16_t pwm; // pwm value for servo
int16_t repeat_count; // number of times to move the servo (returns to trim in between)
uint16_t time_ms; // cycle time in milliseconds (the time between peaks or the time the servo is at the specified pwm value for each cycle?)
float cycle_time; // cycle time in seconds (the time between peaks or the time the servo is at the specified pwm value for each cycle?)
};
// set cam trigger distance command structure
struct PACKED Cam_Trigg_Distance {
int32_t meters; // distance
float meters; // distance
};
union PACKED Content {
@ -109,12 +120,18 @@ public:
// change speed
Change_Speed_Command speed;
// do-set-relay and do-repeat-relay
// do-set-relay
Set_Relay_Command relay;
// do-set-servo and do-repeate-servo
// do-repeat-relay
Repeat_Relay_Command repeat_relay;
// do-set-servo
Set_Servo_Command servo;
// do-repeate-servo
Repeat_Servo_Command repeat_servo;
// cam trigg distance
Cam_Trigg_Distance cam_trigg_dist;