issue 130, other minor mavlink updates.

git-svn-id: https://arducopter.googlecode.com/svn/trunk@2242 f9c3cf11-9bcb-44bc-f272-b75c42450872
This commit is contained in:
jasonshort 2011-05-11 06:10:06 +00:00
parent e6aa5fc927
commit 1b815410c6
4 changed files with 28 additions and 12 deletions

View File

@ -6,10 +6,12 @@
GCS_MAVLINK::GCS_MAVLINK(AP_Var::Key key) : GCS_MAVLINK::GCS_MAVLINK(AP_Var::Key key) :
packet_drops(0), packet_drops(0),
// parameters // parameters
// note, all values not explicitly initialised here are zeroed // note, all values not explicitly initialised here are zeroed
waypoint_send_timeout(1000), // 1 second waypoint_send_timeout(1000), // 1 second
waypoint_receive_timeout(1000), // 1 second waypoint_receive_timeout(1000), // 1 second
// stream rates // stream rates
_group (key, key == Parameters::k_param_streamrates_port0 ? PSTR("SR0_"): PSTR("SR3_")), _group (key, key == Parameters::k_param_streamrates_port0 ? PSTR("SR0_"): PSTR("SR3_")),
streamRateRawSensors (&_group, 0, 0, PSTR("RAW_SENS")), streamRateRawSensors (&_group, 0, 0, PSTR("RAW_SENS")),
@ -385,6 +387,7 @@ void GCS_MAVLINK::handleMessage(mavlink_message_t* msg)
} else { } else {
frame = MAV_FRAME_GLOBAL; // reference frame frame = MAV_FRAME_GLOBAL; // reference frame
} }
float param1 = 0, param2 = 0 , param3 = 0, param4 = 0; float param1 = 0, param2 = 0 , param3 = 0, param4 = 0;
// time that the mav should loiter in milliseconds // time that the mav should loiter in milliseconds
@ -404,6 +407,7 @@ void GCS_MAVLINK::handleMessage(mavlink_message_t* msg)
} }
} }
switch (tell_command.id) { // Switch to map APM command fields inot MAVLink command fields switch (tell_command.id) { // Switch to map APM command fields inot MAVLink command fields
case MAV_CMD_NAV_LOITER_TURNS: case MAV_CMD_NAV_LOITER_TURNS:
case MAV_CMD_NAV_TAKEOFF: case MAV_CMD_NAV_TAKEOFF:
@ -515,14 +519,8 @@ void GCS_MAVLINK::handleMessage(mavlink_message_t* msg)
mavlink_msg_waypoint_set_current_decode(msg, &packet); mavlink_msg_waypoint_set_current_decode(msg, &packet);
if (mavlink_check_target(packet.target_system,packet.target_component)) break; if (mavlink_check_target(packet.target_system,packet.target_component)) break;
// set current waypoint // set current command
g.waypoint_index.set_and_save(packet.seq); change_command(packet.seq);
{
Location temp; // XXX this is gross
temp = get_command_with_index(packet.seq);
set_next_WP(&temp);
}
mavlink_msg_waypoint_current_send(chan, g.waypoint_index); mavlink_msg_waypoint_current_send(chan, g.waypoint_index);
break; break;

View File

@ -207,8 +207,8 @@ void mavlink_send_message(mavlink_channel_t chan, uint8_t id, uint32_t param, ui
motor_out[2], motor_out[2],
motor_out[3], motor_out[3],
motor_out[4], motor_out[4],
motor_out[5], g.rc_5.radio_out,
motor_out[6], g.rc_6.radio_out,
motor_out[7]); motor_out[7]);
break; break;
} }
@ -220,7 +220,7 @@ void mavlink_send_message(mavlink_channel_t chan, uint8_t id, uint32_t param, ui
(float)airspeed / 100.0, (float)airspeed / 100.0,
(float)g_gps->ground_speed / 100.0, (float)g_gps->ground_speed / 100.0,
(dcm.yaw_sensor / 100) % 360, (dcm.yaw_sensor / 100) % 360,
nav_throttle, (int)g.rc_3.servo_out,
current_loc.alt / 100.0, current_loc.alt / 100.0,
climb_rate); climb_rate);
break; break;

View File

@ -1,5 +1,22 @@
/// -*- tab-width: 4; Mode: C++; c-basic-offset: 4; indent-tabs-mode: nil -*- /// -*- tab-width: 4; Mode: C++; c-basic-offset: 4; indent-tabs-mode: nil -*-
// For changing active command mid-mission
//----------------------------------------
void change_command(uint8_t index)
{
struct Location temp = get_command_with_index(index);
if (next_command.id > MAV_CMD_NAV_LAST ){
gcs.send_text_P(SEVERITY_LOW,PSTR("error: non-Nav cmd"));
} else {
command_must_index = NO_COMMAND;
next_command.id = NO_COMMAND;
g.waypoint_index.set_and_save(index - 1);
update_commands();
}
}
// called by 10 Hz Medium loop // called by 10 Hz Medium loop
// --------------------------- // ---------------------------
void update_commands(void) void update_commands(void)

View File

@ -773,7 +773,8 @@ test_altitude(uint8_t argc, const Menu::arg *argv)
// decide which sensor we're usings // decide which sensor we're usings
sonar_alt = sonar.read(); sonar_alt = sonar.read();
} }
Serial.printf_P(PSTR("B_alt: %ld, S_alt: %ld\n"),
Serial.printf_P(PSTR("B_alt: %d, S_alt: %d\n"),
baro_alt, baro_alt,
sonar_alt); sonar_alt);