mirror of https://github.com/ArduPilot/ardupilot
HIL: enable reception of GPS and ATTITUDE via MAVLink
this allows us to get GPS position and ATTITUDE in HIL_MODE_ATTITUDE git-svn-id: https://arducopter.googlecode.com/svn/trunk@2893 f9c3cf11-9bcb-44bc-f272-b75c42450872
This commit is contained in:
parent
e6a46d888f
commit
1a35209e5d
|
@ -861,7 +861,7 @@ void GCS_MAVLINK::handleMessage(mavlink_message_t* msg)
|
||||||
|
|
||||||
break;
|
break;
|
||||||
} // end case
|
} // end case
|
||||||
/*
|
|
||||||
case MAVLINK_MSG_ID_RC_CHANNELS_OVERRIDE:
|
case MAVLINK_MSG_ID_RC_CHANNELS_OVERRIDE:
|
||||||
{
|
{
|
||||||
// allow override of RC channel values for HIL
|
// allow override of RC channel values for HIL
|
||||||
|
@ -883,11 +883,42 @@ void GCS_MAVLINK::handleMessage(mavlink_message_t* msg)
|
||||||
v[5] = packet.chan6_raw;
|
v[5] = packet.chan6_raw;
|
||||||
v[6] = packet.chan7_raw;
|
v[6] = packet.chan7_raw;
|
||||||
v[7] = packet.chan8_raw;
|
v[7] = packet.chan8_raw;
|
||||||
rc_override_active = APM_RC.setHIL(v);
|
APM_RC.setHIL(v);
|
||||||
rc_override_fs_timer = millis();
|
|
||||||
break;
|
break;
|
||||||
}
|
}
|
||||||
|
|
||||||
|
#if HIL_MODE != HIL_MODE_DISABLED
|
||||||
|
// This is used both as a sensor and to pass the location
|
||||||
|
// in HIL_ATTITUDE mode.
|
||||||
|
case MAVLINK_MSG_ID_GPS_RAW:
|
||||||
|
{
|
||||||
|
// decode
|
||||||
|
mavlink_gps_raw_t packet;
|
||||||
|
mavlink_msg_gps_raw_decode(msg, &packet);
|
||||||
|
|
||||||
|
// set gps hil sensor
|
||||||
|
g_gps->setHIL(packet.usec/1000.0,packet.lat,packet.lon,packet.alt,
|
||||||
|
packet.v,packet.hdg,0,0);
|
||||||
|
current_loc.lng = packet.lon * T7;
|
||||||
|
current_loc.lat = packet.lat * T7;
|
||||||
|
current_loc.alt = packet.alt * 10;
|
||||||
|
break;
|
||||||
|
}
|
||||||
|
#if HIL_MODE == HIL_MODE_ATTITUDE
|
||||||
|
case MAVLINK_MSG_ID_ATTITUDE:
|
||||||
|
{
|
||||||
|
// decode
|
||||||
|
mavlink_attitude_t packet;
|
||||||
|
mavlink_msg_attitude_decode(msg, &packet);
|
||||||
|
|
||||||
|
// set dcm hil sensor
|
||||||
|
dcm.setHil(packet.roll,packet.pitch,packet.yaw,packet.rollspeed,
|
||||||
|
packet.pitchspeed,packet.yawspeed);
|
||||||
|
break;
|
||||||
|
}
|
||||||
|
#endif
|
||||||
|
#endif
|
||||||
|
/*
|
||||||
case MAVLINK_MSG_ID_HEARTBEAT:
|
case MAVLINK_MSG_ID_HEARTBEAT:
|
||||||
{
|
{
|
||||||
// We keep track of the last time we received a heartbeat from our GCS for failsafe purposes
|
// We keep track of the last time we received a heartbeat from our GCS for failsafe purposes
|
||||||
|
|
Loading…
Reference in New Issue