2011-03-19 07:20:11 -03:00
|
|
|
/// -*- tab-width: 4; Mode: C++; c-basic-offset: 4; indent-tabs-mode: nil -*-
|
2011-03-03 07:39:52 -04:00
|
|
|
|
2011-02-17 03:09:13 -04:00
|
|
|
#ifndef Mavlink_Common_H
|
|
|
|
#define Mavlink_Common_H
|
|
|
|
|
|
|
|
#if HIL_PROTOCOL == HIL_PROTOCOL_MAVLINK || GCS_PROTOCOL == GCS_PROTOCOL_MAVLINK
|
|
|
|
|
|
|
|
byte mavdelay = 0;
|
|
|
|
|
2011-05-09 14:40:32 -03:00
|
|
|
|
2011-03-13 03:25:38 -03:00
|
|
|
// what does this do?
|
2011-02-17 03:09:13 -04:00
|
|
|
static uint8_t mavlink_check_target(uint8_t sysid, uint8_t compid)
|
|
|
|
{
|
2011-05-09 14:40:32 -03:00
|
|
|
//Serial.print("target = "); Serial.print(sysid, DEC); Serial.print("\tcomp = "); Serial.println(compid, DEC);
|
2011-03-09 02:37:09 -04:00
|
|
|
if (sysid != mavlink_system.sysid){
|
2011-02-17 03:09:13 -04:00
|
|
|
return 1;
|
2011-03-09 02:37:09 -04:00
|
|
|
|
|
|
|
}else if(compid != mavlink_system.compid){
|
2011-03-19 07:14:15 -03:00
|
|
|
gcs.send_text_P(SEVERITY_LOW,PSTR("component id mismatch"));
|
2011-02-17 03:09:13 -04:00
|
|
|
return 0; // XXX currently not receiving correct compid from gcs
|
2011-03-09 02:37:09 -04:00
|
|
|
|
2011-03-13 03:25:38 -03:00
|
|
|
}else{
|
2011-03-09 02:37:09 -04:00
|
|
|
return 0; // no error
|
2011-02-17 03:09:13 -04:00
|
|
|
}
|
|
|
|
}
|
|
|
|
|
2011-05-09 14:40:32 -03:00
|
|
|
|
2011-02-17 03:09:13 -04:00
|
|
|
void mavlink_send_message(mavlink_channel_t chan, uint8_t id, uint32_t param, uint16_t packet_drops)
|
|
|
|
{
|
|
|
|
uint64_t timeStamp = micros();
|
2011-03-09 02:37:09 -04:00
|
|
|
switch(id) {
|
2011-02-17 03:09:13 -04:00
|
|
|
|
2011-03-09 02:37:09 -04:00
|
|
|
case MSG_HEARTBEAT:
|
|
|
|
mavlink_msg_heartbeat_send(
|
|
|
|
chan,
|
2011-04-15 10:24:05 -03:00
|
|
|
mavlink_system.type,
|
2011-03-09 02:37:09 -04:00
|
|
|
MAV_AUTOPILOT_ARDUPILOTMEGA);
|
|
|
|
break;
|
2011-02-17 03:09:13 -04:00
|
|
|
|
2011-03-09 02:37:09 -04:00
|
|
|
case MSG_EXTENDED_STATUS:
|
|
|
|
{
|
|
|
|
uint8_t mode = MAV_MODE_UNINIT;
|
|
|
|
uint8_t nav_mode = MAV_NAV_VECTOR;
|
2011-02-17 03:09:13 -04:00
|
|
|
|
2011-03-09 02:37:09 -04:00
|
|
|
switch(control_mode) {
|
|
|
|
case ACRO:
|
2011-03-13 03:25:38 -03:00
|
|
|
mode = MAV_MODE_MANUAL;
|
2011-03-09 02:37:09 -04:00
|
|
|
break;
|
|
|
|
case STABILIZE:
|
2011-03-13 03:25:38 -03:00
|
|
|
mode = MAV_MODE_GUIDED;
|
2011-03-09 02:37:09 -04:00
|
|
|
break;
|
2011-04-08 16:13:31 -03:00
|
|
|
case SIMPLE:
|
2011-03-13 03:25:38 -03:00
|
|
|
mode = MAV_MODE_TEST1;
|
2011-03-09 02:37:09 -04:00
|
|
|
break;
|
|
|
|
case ALT_HOLD:
|
2011-03-13 03:25:38 -03:00
|
|
|
mode = MAV_MODE_TEST2;
|
2011-03-09 02:37:09 -04:00
|
|
|
break;
|
|
|
|
case LOITER:
|
2011-03-13 03:25:38 -03:00
|
|
|
mode = MAV_MODE_AUTO;
|
|
|
|
nav_mode = MAV_NAV_HOLD;
|
2011-03-09 02:37:09 -04:00
|
|
|
break;
|
|
|
|
case AUTO:
|
2011-03-13 03:25:38 -03:00
|
|
|
mode = MAV_MODE_AUTO;
|
|
|
|
nav_mode = MAV_NAV_WAYPOINT;
|
2011-03-09 02:37:09 -04:00
|
|
|
break;
|
|
|
|
case RTL:
|
2011-03-13 03:25:38 -03:00
|
|
|
mode = MAV_MODE_AUTO;
|
|
|
|
nav_mode = MAV_NAV_RETURNING;
|
2011-03-09 02:37:09 -04:00
|
|
|
break;
|
|
|
|
}
|
2011-03-13 03:25:38 -03:00
|
|
|
|
2011-03-09 02:37:09 -04:00
|
|
|
uint8_t status = MAV_STATE_ACTIVE;
|
2011-05-09 14:40:32 -03:00
|
|
|
uint16_t battery_remaining = 10.0 * (float)(g.pack_capacity - current_total)/g.pack_capacity; //Mavlink scaling 100% = 1000
|
2011-03-09 02:37:09 -04:00
|
|
|
uint8_t motor_block = false;
|
|
|
|
|
|
|
|
mavlink_msg_sys_status_send(
|
|
|
|
chan,
|
|
|
|
mode,
|
|
|
|
nav_mode,
|
|
|
|
status,
|
|
|
|
load * 1000,
|
2011-05-09 14:40:32 -03:00
|
|
|
battery_voltage * 1000,
|
2011-03-09 02:37:09 -04:00
|
|
|
motor_block,
|
|
|
|
packet_drops);
|
2011-02-17 03:09:13 -04:00
|
|
|
break;
|
2011-03-09 02:37:09 -04:00
|
|
|
}
|
|
|
|
|
|
|
|
case MSG_ATTITUDE:
|
|
|
|
{
|
2011-05-06 21:21:16 -03:00
|
|
|
//Vector3f omega = dcm.get_gyro();
|
2011-03-09 02:37:09 -04:00
|
|
|
mavlink_msg_attitude_send(
|
|
|
|
chan,
|
|
|
|
timeStamp,
|
|
|
|
dcm.roll,
|
|
|
|
dcm.pitch,
|
|
|
|
dcm.yaw,
|
|
|
|
omega.x,
|
|
|
|
omega.y,
|
|
|
|
omega.z);
|
2011-02-17 03:09:13 -04:00
|
|
|
break;
|
2011-03-09 02:37:09 -04:00
|
|
|
}
|
|
|
|
|
|
|
|
case MSG_LOCATION:
|
|
|
|
{
|
|
|
|
Matrix3f rot = dcm.get_dcm_matrix(); // neglecting angle of attack for now
|
|
|
|
mavlink_msg_global_position_int_send(
|
|
|
|
chan,
|
|
|
|
current_loc.lat,
|
|
|
|
current_loc.lng,
|
|
|
|
current_loc.alt * 10,
|
2011-03-13 03:25:38 -03:00
|
|
|
g_gps->ground_speed * rot.a.x,
|
|
|
|
g_gps->ground_speed * rot.b.x,
|
|
|
|
g_gps->ground_speed * rot.c.x);
|
2011-02-17 03:09:13 -04:00
|
|
|
break;
|
|
|
|
}
|
|
|
|
|
2011-05-09 14:40:32 -03:00
|
|
|
case MSG_NAV_CONTROLLER_OUTPUT:
|
|
|
|
{
|
|
|
|
//if (control_mode != MANUAL) {
|
|
|
|
mavlink_msg_nav_controller_output_send(
|
|
|
|
chan,
|
|
|
|
nav_roll / 1.0e2,
|
|
|
|
nav_pitch / 1.0e2,
|
|
|
|
nav_bearing / 1.0e2,
|
|
|
|
target_bearing / 1.0e2,
|
|
|
|
wp_distance,
|
|
|
|
altitude_error / 1.0e2,
|
|
|
|
0,
|
|
|
|
crosstrack_error);
|
|
|
|
//}
|
|
|
|
break;
|
|
|
|
}
|
|
|
|
|
2011-03-09 02:37:09 -04:00
|
|
|
case MSG_LOCAL_LOCATION:
|
|
|
|
{
|
|
|
|
Matrix3f rot = dcm.get_dcm_matrix(); // neglecting angle of attack for now
|
|
|
|
mavlink_msg_local_position_send(
|
|
|
|
chan,
|
|
|
|
timeStamp,
|
|
|
|
ToRad((current_loc.lat - home.lat) / 1.0e7) * radius_of_earth,
|
|
|
|
ToRad((current_loc.lng - home.lng) / 1.0e7) * radius_of_earth * cos(ToRad(home.lat / 1.0e7)),
|
|
|
|
(current_loc.alt - home.alt) / 1.0e2,
|
|
|
|
g_gps->ground_speed / 1.0e2 * rot.a.x,
|
|
|
|
g_gps->ground_speed / 1.0e2 * rot.b.x,
|
|
|
|
g_gps->ground_speed / 1.0e2 * rot.c.x);
|
|
|
|
break;
|
|
|
|
}
|
2011-02-17 03:09:13 -04:00
|
|
|
|
2011-03-09 02:37:09 -04:00
|
|
|
case MSG_GPS_RAW:
|
|
|
|
{
|
|
|
|
mavlink_msg_gps_raw_send(
|
|
|
|
chan,
|
|
|
|
timeStamp,
|
|
|
|
g_gps->status(),
|
|
|
|
g_gps->latitude / 1.0e7,
|
|
|
|
g_gps->longitude / 1.0e7,
|
|
|
|
g_gps->altitude / 100.0,
|
|
|
|
g_gps->hdop,
|
|
|
|
0.0,
|
|
|
|
g_gps->ground_speed / 100.0,
|
|
|
|
g_gps->ground_course / 100.0);
|
|
|
|
break;
|
|
|
|
}
|
2011-03-02 22:32:50 -04:00
|
|
|
|
2011-03-09 02:37:09 -04:00
|
|
|
case MSG_SERVO_OUT:
|
|
|
|
{
|
|
|
|
uint8_t rssi = 1;
|
|
|
|
// normalized values scaled to -10000 to 10000
|
|
|
|
// This is used for HIL. Do not change without discussing with HIL maintainers
|
|
|
|
mavlink_msg_rc_channels_scaled_send(
|
|
|
|
chan,
|
2011-04-15 10:24:05 -03:00
|
|
|
10000 * g.rc_1.norm_output(),
|
|
|
|
10000 * g.rc_2.norm_output(),
|
|
|
|
10000 * g.rc_3.norm_output(),
|
|
|
|
10000 * g.rc_4.norm_output(),
|
2011-03-13 03:25:38 -03:00
|
|
|
0,
|
|
|
|
0,
|
|
|
|
0,
|
|
|
|
0,
|
|
|
|
rssi);
|
2011-03-09 02:37:09 -04:00
|
|
|
break;
|
|
|
|
}
|
2011-03-02 22:32:50 -04:00
|
|
|
|
2011-03-09 02:37:09 -04:00
|
|
|
case MSG_RADIO_IN:
|
|
|
|
{
|
|
|
|
uint8_t rssi = 1;
|
|
|
|
mavlink_msg_rc_channels_raw_send(
|
|
|
|
chan,
|
|
|
|
g.rc_1.radio_in,
|
|
|
|
g.rc_2.radio_in,
|
|
|
|
g.rc_3.radio_in,
|
|
|
|
g.rc_4.radio_in,
|
|
|
|
g.rc_5.radio_in,
|
|
|
|
g.rc_6.radio_in,
|
|
|
|
g.rc_7.radio_in,
|
|
|
|
g.rc_8.radio_in,
|
|
|
|
rssi);
|
|
|
|
break;
|
|
|
|
}
|
2011-03-02 22:32:50 -04:00
|
|
|
|
2011-03-09 02:37:09 -04:00
|
|
|
case MSG_RADIO_OUT:
|
|
|
|
{
|
|
|
|
mavlink_msg_servo_output_raw_send(
|
|
|
|
chan,
|
|
|
|
motor_out[0],
|
|
|
|
motor_out[1],
|
|
|
|
motor_out[2],
|
|
|
|
motor_out[3],
|
2011-04-16 04:36:22 -03:00
|
|
|
motor_out[4],
|
|
|
|
motor_out[5],
|
|
|
|
motor_out[6],
|
|
|
|
motor_out[7]);
|
2011-03-09 02:37:09 -04:00
|
|
|
break;
|
|
|
|
}
|
2011-03-02 22:32:50 -04:00
|
|
|
|
2011-03-09 02:37:09 -04:00
|
|
|
case MSG_VFR_HUD:
|
|
|
|
{
|
|
|
|
mavlink_msg_vfr_hud_send(
|
|
|
|
chan,
|
|
|
|
(float)airspeed / 100.0,
|
|
|
|
(float)g_gps->ground_speed / 100.0,
|
2011-04-15 10:24:05 -03:00
|
|
|
(dcm.yaw_sensor / 100) % 360,
|
|
|
|
nav_throttle,
|
2011-03-09 02:37:09 -04:00
|
|
|
current_loc.alt / 100.0,
|
2011-04-15 10:24:05 -03:00
|
|
|
climb_rate);
|
2011-03-09 02:37:09 -04:00
|
|
|
break;
|
|
|
|
}
|
2011-03-02 22:32:50 -04:00
|
|
|
|
2011-03-09 02:37:09 -04:00
|
|
|
#if HIL_MODE != HIL_MODE_ATTITUDE
|
|
|
|
case MSG_RAW_IMU:
|
|
|
|
{
|
|
|
|
Vector3f accel = imu.get_accel();
|
|
|
|
Vector3f gyro = imu.get_gyro();
|
|
|
|
//Serial.printf_P(PSTR("sending accel: %f %f %f\n"), accel.x, accel.y, accel.z);
|
|
|
|
//Serial.printf_P(PSTR("sending gyro: %f %f %f\n"), gyro.x, gyro.y, gyro.z);
|
|
|
|
mavlink_msg_raw_imu_send(
|
|
|
|
chan,
|
|
|
|
timeStamp,
|
|
|
|
accel.x * 1000.0 / gravity,
|
|
|
|
accel.y * 1000.0 / gravity,
|
|
|
|
accel.z * 1000.0 / gravity,
|
|
|
|
gyro.x * 1000.0,
|
|
|
|
gyro.y * 1000.0,
|
|
|
|
gyro.z * 1000.0,
|
|
|
|
compass.mag_x,
|
|
|
|
compass.mag_y,
|
|
|
|
compass.mag_z);
|
2011-03-02 22:32:50 -04:00
|
|
|
|
2011-03-09 02:37:09 -04:00
|
|
|
mavlink_msg_raw_pressure_send(
|
|
|
|
chan,
|
|
|
|
timeStamp,
|
|
|
|
adc.Ch(AIRSPEED_CH),
|
|
|
|
barometer.RawPress,
|
|
|
|
0,
|
|
|
|
0);
|
|
|
|
break;
|
|
|
|
}
|
|
|
|
#endif // HIL_PROTOCOL != HIL_PROTOCOL_ATTITUDE
|
2011-03-02 22:32:50 -04:00
|
|
|
|
2011-03-09 02:37:09 -04:00
|
|
|
case MSG_GPS_STATUS:
|
|
|
|
{
|
|
|
|
mavlink_msg_gps_status_send(
|
|
|
|
chan,
|
|
|
|
g_gps->num_sats,
|
|
|
|
NULL,
|
|
|
|
NULL,
|
|
|
|
NULL,
|
|
|
|
NULL,
|
|
|
|
NULL);
|
|
|
|
break;
|
|
|
|
}
|
2011-02-17 03:09:13 -04:00
|
|
|
|
2011-03-09 02:37:09 -04:00
|
|
|
case MSG_CURRENT_WAYPOINT:
|
|
|
|
{
|
|
|
|
mavlink_msg_waypoint_current_send(
|
|
|
|
chan,
|
|
|
|
g.waypoint_index);
|
|
|
|
break;
|
|
|
|
}
|
2011-03-02 22:32:50 -04:00
|
|
|
|
2011-04-15 10:24:05 -03:00
|
|
|
default:
|
2011-03-09 02:37:09 -04:00
|
|
|
break;
|
2011-03-02 22:32:50 -04:00
|
|
|
}
|
2011-02-17 03:09:13 -04:00
|
|
|
}
|
|
|
|
|
|
|
|
void mavlink_send_text(mavlink_channel_t chan, uint8_t severity, const char *str)
|
|
|
|
{
|
2011-03-02 22:32:50 -04:00
|
|
|
mavlink_msg_statustext_send(
|
2011-03-05 01:15:12 -04:00
|
|
|
chan,
|
|
|
|
severity,
|
|
|
|
(const int8_t*) str);
|
2011-02-17 03:09:13 -04:00
|
|
|
}
|
|
|
|
|
|
|
|
void mavlink_acknowledge(mavlink_channel_t chan, uint8_t id, uint8_t sum1, uint8_t sum2)
|
|
|
|
{
|
|
|
|
}
|
|
|
|
|
|
|
|
#endif // mavlink in use
|
|
|
|
|
2011-05-06 21:21:16 -03:00
|
|
|
#endif // inclusion guard
|