Merge branch 'mavlink2_hil' of github.com:PX4/Firmware into paul_estimator_mavlink2

This commit is contained in:
Lorenz Meier 2014-03-11 21:12:26 +01:00
commit 4bcdf5f72f
3 changed files with 27 additions and 104 deletions

View File

@ -5,7 +5,7 @@
echo "Starting MAVLink on this USB console" echo "Starting MAVLink on this USB console"
mavlink start -r 5000 -d /dev/ttyACM0 mavlink start -r 10000 -d /dev/ttyACM0
# Exit shell to make it available to MAVLink # Exit shell to make it available to MAVLink
exit exit

View File

@ -165,7 +165,7 @@ Mavlink::Mavlink() :
_task_should_exit(false), _task_should_exit(false),
_mavlink_fd(-1), _mavlink_fd(-1),
_task_running(false), _task_running(false),
_mavlink_hil_enabled(false), _hil_enabled(false),
_main_loop_delay(1000), _main_loop_delay(1000),
_subscriptions(nullptr), _subscriptions(nullptr),
_streams(nullptr), _streams(nullptr),
@ -548,38 +548,17 @@ Mavlink::set_hil_enabled(bool hil_enabled)
{ {
int ret = OK; int ret = OK;
/* Enable HIL */ /* enable HIL */
if (hil_enabled && !_mavlink_hil_enabled) { if (hil_enabled && !_hil_enabled) {
_hil_enabled = true;
_mavlink_hil_enabled = true; float rate_mult = _datarate / 1000.0f;
configure_stream("HIL_CONTROLS", 15.0f * rate_mult);
/* ramp up some HIL-related subscriptions */
unsigned hil_rate_interval;
if (_baudrate < 19200) {
/* 10 Hz */
hil_rate_interval = 100;
} else if (_baudrate < 38400) {
/* 10 Hz */
hil_rate_interval = 100;
} else if (_baudrate < 115200) {
/* 20 Hz */
hil_rate_interval = 50;
} else {
/* 200 Hz */
hil_rate_interval = 5;
}
// orb_set_interval(subs.spa_sub, hil_rate_interval);
// set_mavlink_interval_limit(MAVLINK_MSG_ID_SERVO_OUTPUT_RAW, hil_rate_interval);
} }
if (!hil_enabled && _mavlink_hil_enabled) { /* disable HIL */
_mavlink_hil_enabled = false; if (!hil_enabled && _hil_enabled) {
// orb_set_interval(subs.spa_sub, 200); _hil_enabled = false;
configure_stream("HIL_CONTROLS", 0.0f);
} else { } else {
ret = ERROR; ret = ERROR;
@ -1445,10 +1424,8 @@ Mavlink::mavlink_missionlib_send_gcs_string(const char *string)
if (i > 1) { if (i > 1) {
/* Enforce null termination */ /* Enforce null termination */
statustext.text[i] = '\0'; statustext.text[i] = '\0';
mavlink_message_t msg;
mavlink_msg_statustext_encode(mavlink_system.sysid, mavlink_system.compid, &msg, &statustext); mavlink_msg_statustext_send(_channel, statustext.severity, statustext.text);
mavlink_missionlib_send_message(&msg);
return OK; return OK;
} else { } else {
@ -1560,9 +1537,7 @@ Mavlink::task_main(int argc, char *argv[])
int ch; int ch;
_baudrate = 57600; _baudrate = 57600;
_datarate = 0; _datarate = 0;
_channel = MAVLINK_COMM_0; _mode = MAVLINK_MODE_NORMAL;
_mode = MODE_OFFBOARD;
/* work around some stupidity in task_create's argv handling */ /* work around some stupidity in task_create's argv handling */
argc -= 2; argc -= 2;
@ -1603,17 +1578,8 @@ Mavlink::task_main(int argc, char *argv[])
// break; // break;
case 'm': case 'm':
if (strcmp(optarg, "offboard") == 0) { if (strcmp(optarg, "custom") == 0) {
_mode = MODE_OFFBOARD; _mode = MAVLINK_MODE_CUSTOM;
} else if (strcmp(optarg, "onboard") == 0) {
_mode = MODE_ONBOARD;
} else if (strcmp(optarg, "hil") == 0) {
_mode = MODE_HIL;
} else if (strcmp(optarg, "custom") == 0) {
_mode = MODE_CUSTOM;
} }
break; break;
@ -1649,42 +1615,20 @@ Mavlink::task_main(int argc, char *argv[])
/* inform about mode */ /* inform about mode */
switch (_mode) { switch (_mode) {
case MODE_CUSTOM: case MAVLINK_MODE_NORMAL:
warnx("mode: NORMAL");
break;
case MAVLINK_MODE_CUSTOM:
warnx("mode: CUSTOM"); warnx("mode: CUSTOM");
break; break;
case MODE_OFFBOARD:
warnx("mode: OFFBOARD");
break;
case MODE_ONBOARD:
warnx("mode: ONBOARD");
break;
case MODE_HIL:
warnx("mode: HIL");
break;
default: default:
warnx("ERROR: Unknown mode"); warnx("ERROR: Unknown mode");
break; break;
} }
switch (_mode) { _mavlink_wpm_comp_id = MAV_COMP_ID_MISSIONPLANNER;
case MODE_OFFBOARD:
case MODE_HIL:
case MODE_CUSTOM:
_mavlink_wpm_comp_id = MAV_COMP_ID_MISSIONPLANNER;
break;
case MODE_ONBOARD:
_mavlink_wpm_comp_id = MAV_COMP_ID_CAMERA;
break;
default:
_mavlink_wpm_comp_id = MAV_COMP_ID_ALL;
break;
}
warnx("data rate: %d bytes/s", _datarate); warnx("data rate: %d bytes/s", _datarate);
warnx("port: %s, baudrate: %d", _device_name, _baudrate); warnx("port: %s, baudrate: %d", _device_name, _baudrate);
@ -1741,7 +1685,7 @@ Mavlink::task_main(int argc, char *argv[])
configure_stream("HEARTBEAT", 1.0f); configure_stream("HEARTBEAT", 1.0f);
switch (_mode) { switch (_mode) {
case MODE_OFFBOARD: case MAVLINK_MODE_NORMAL:
configure_stream("SYS_STATUS", 1.0f); configure_stream("SYS_STATUS", 1.0f);
configure_stream("GPS_GLOBAL_ORIGIN", 0.5f); configure_stream("GPS_GLOBAL_ORIGIN", 0.5f);
configure_stream("HIGHRES_IMU", 1.0f * rate_mult); configure_stream("HIGHRES_IMU", 1.0f * rate_mult);
@ -1753,20 +1697,6 @@ Mavlink::task_main(int argc, char *argv[])
configure_stream("RC_CHANNELS_RAW", 1.0f * rate_mult); configure_stream("RC_CHANNELS_RAW", 1.0f * rate_mult);
break; break;
case MODE_HIL:
/* HIL mode normally runs at high data rate, rate_mult ~ 10 */
configure_stream("SYS_STATUS", 1.0f);
configure_stream("GPS_GLOBAL_ORIGIN", 0.5f);
configure_stream("HIGHRES_IMU", 1.0f * rate_mult);
configure_stream("ATTITUDE", 2.0f * rate_mult);
configure_stream("VFR_HUD", 2.0f * rate_mult);
configure_stream("GPS_RAW_INT", 1.0f * rate_mult);
configure_stream("GLOBAL_POSITION_INT", 1.0f * rate_mult);
configure_stream("LOCAL_POSITION_NED", 1.0f * rate_mult);
configure_stream("RC_CHANNELS_RAW", 1.0f * rate_mult);
configure_stream("HIL_CONTROLS", 15.0f * rate_mult);
break;
default: default:
break; break;
} }
@ -1795,12 +1725,7 @@ Mavlink::task_main(int argc, char *argv[])
if (status_sub->update(t)) { if (status_sub->update(t)) {
/* switch HIL mode if required */ /* switch HIL mode if required */
if (status->hil_state == HIL_STATE_ON) { set_hil_enabled(status->hil_state == HIL_STATE_ON);
set_hil_enabled(true);
} else if (status->hil_state == HIL_STATE_OFF) {
set_hil_enabled(false);
}
} }
/* check for requested subscriptions */ /* check for requested subscriptions */

View File

@ -145,16 +145,14 @@ public:
const char *_device_name; const char *_device_name;
enum MAVLINK_MODE { enum MAVLINK_MODE {
MODE_CUSTOM = 0, MAVLINK_MODE_NORMAL = 0,
MODE_OFFBOARD, MAVLINK_MODE_CUSTOM
MODE_ONBOARD,
MODE_HIL
}; };
void set_mode(enum MAVLINK_MODE); void set_mode(enum MAVLINK_MODE);
enum MAVLINK_MODE get_mode() { return _mode; } enum MAVLINK_MODE get_mode() { return _mode; }
bool get_hil_enabled() { return _mavlink_hil_enabled; }; bool get_hil_enabled() { return _hil_enabled; };
/** /**
* Handle waypoint related messages. * Handle waypoint related messages.
@ -200,7 +198,7 @@ private:
perf_counter_t _loop_perf; /**< loop performance counter */ perf_counter_t _loop_perf; /**< loop performance counter */
/* states */ /* states */
bool _mavlink_hil_enabled; /**< Hardware In the Loop mode */ bool _hil_enabled; /**< Hardware In the Loop mode */
unsigned _main_loop_delay; /**< mainloop delay, depends on data rate */ unsigned _main_loop_delay; /**< mainloop delay, depends on data rate */