aboutsummaryrefslogtreecommitdiff
path: root/src/modules/mavlink/mavlink_receiver.cpp
diff options
context:
space:
mode:
Diffstat (limited to 'src/modules/mavlink/mavlink_receiver.cpp')
-rw-r--r--src/modules/mavlink/mavlink_receiver.cpp50
1 files changed, 33 insertions, 17 deletions
diff --git a/src/modules/mavlink/mavlink_receiver.cpp b/src/modules/mavlink/mavlink_receiver.cpp
index ce3f2ae0e..4d7b35f03 100644
--- a/src/modules/mavlink/mavlink_receiver.cpp
+++ b/src/modules/mavlink/mavlink_receiver.cpp
@@ -92,6 +92,7 @@ MavlinkReceiver::MavlinkReceiver(Mavlink *parent) :
_mavlink(parent),
status{},
hil_local_pos{},
+ hil_land_detector{},
_control_mode{},
_global_pos_pub(-1),
_local_pos_pub(-1),
@@ -118,6 +119,7 @@ MavlinkReceiver::MavlinkReceiver(Mavlink *parent) :
_telemetry_status_pub(-1),
_rc_pub(-1),
_manual_pub(-1),
+ _land_detector_pub(-1),
_control_mode_sub(orb_subscribe(ORB_ID(vehicle_control_mode))),
_hil_frames(0),
_old_timestamp(0),
@@ -433,7 +435,7 @@ MavlinkReceiver::handle_message_hil_optical_flow(mavlink_message_t *msg)
/* Use distance value for range finder report */
struct range_finder_report r;
- memset(&r, 0, sizeof(f));
+ memset(&r, 0, sizeof(r));
r.timestamp = hrt_absolute_time();
r.error_count = 0;
@@ -615,7 +617,7 @@ MavlinkReceiver::handle_message_set_position_target_local_ned(mavlink_message_t
pos_sp_triplet.previous.valid = false;
pos_sp_triplet.next.valid = false;
pos_sp_triplet.current.valid = true;
- pos_sp_triplet.current.type = SETPOINT_TYPE_POSITION; //XXX support others
+ pos_sp_triplet.current.type = position_setpoint_s::SETPOINT_TYPE_POSITION; //XXX support others
/* set the local pos values if the setpoint type is 'local pos' and none
* of the local pos fields is set to 'ignore' */
@@ -984,10 +986,10 @@ MavlinkReceiver::handle_message_timesync(mavlink_message_t *msg)
} else if (tsync.tc1 > 0) {
- int64_t offset_ns = (tsync.ts1 + now_ns - tsync.tc1*2)/2 ;
+ int64_t offset_ns = (tsync.ts1 + now_ns - tsync.tc1*2)/2 ;
int64_t dt = _time_offset - offset_ns;
- if (dt > 10000000LL || dt < -10000000LL) { // 10 millisecond skew
+ if (dt > 10000000LL || dt < -10000000LL) { // 10 millisecond skew
_time_offset = offset_ns;
warnx("[timesync] Hard setting offset.");
} else {
@@ -1041,10 +1043,10 @@ MavlinkReceiver::handle_message_hil_sensor(mavlink_message_t *msg)
gyro.temperature = imu.temperature;
if (_gyro_pub < 0) {
- _gyro_pub = orb_advertise(ORB_ID(sensor_gyro0), &gyro);
+ _gyro_pub = orb_advertise(ORB_ID(sensor_gyro), &gyro);
} else {
- orb_publish(ORB_ID(sensor_gyro0), _gyro_pub, &gyro);
+ orb_publish(ORB_ID(sensor_gyro), _gyro_pub, &gyro);
}
}
@@ -1063,10 +1065,10 @@ MavlinkReceiver::handle_message_hil_sensor(mavlink_message_t *msg)
accel.temperature = imu.temperature;
if (_accel_pub < 0) {
- _accel_pub = orb_advertise(ORB_ID(sensor_accel0), &accel);
+ _accel_pub = orb_advertise(ORB_ID(sensor_accel), &accel);
} else {
- orb_publish(ORB_ID(sensor_accel0), _accel_pub, &accel);
+ orb_publish(ORB_ID(sensor_accel), _accel_pub, &accel);
}
}
@@ -1084,10 +1086,11 @@ MavlinkReceiver::handle_message_hil_sensor(mavlink_message_t *msg)
mag.z = imu.zmag;
if (_mag_pub < 0) {
- _mag_pub = orb_advertise(ORB_ID(sensor_mag0), &mag);
+ /* publish to the first mag topic */
+ _mag_pub = orb_advertise(ORB_ID(sensor_mag), &mag);
} else {
- orb_publish(ORB_ID(sensor_mag0), _mag_pub, &mag);
+ orb_publish(ORB_ID(sensor_mag), _mag_pub, &mag);
}
}
@@ -1102,10 +1105,10 @@ MavlinkReceiver::handle_message_hil_sensor(mavlink_message_t *msg)
baro.temperature = imu.temperature;
if (_baro_pub < 0) {
- _baro_pub = orb_advertise(ORB_ID(sensor_baro0), &baro);
+ _baro_pub = orb_advertise(ORB_ID(sensor_baro), &baro);
} else {
- orb_publish(ORB_ID(sensor_baro0), _baro_pub, &baro);
+ orb_publish(ORB_ID(sensor_baro), _baro_pub, &baro);
}
}
@@ -1353,9 +1356,6 @@ MavlinkReceiver::handle_message_hil_state_quaternion(mavlink_message_t *msg)
hil_local_pos.xy_global = true;
hil_local_pos.z_global = true;
- bool landed = (float)(hil_state.alt) / 1000.0f < (_hil_local_alt0 + 0.1f); // XXX improve?
- hil_local_pos.landed = landed;
-
if (_local_pos_pub < 0) {
_local_pos_pub = orb_advertise(ORB_ID(vehicle_local_position), &hil_local_pos);
@@ -1364,6 +1364,22 @@ MavlinkReceiver::handle_message_hil_state_quaternion(mavlink_message_t *msg)
}
}
+ /* land detector */
+ {
+ bool landed = (float)(hil_state.alt) / 1000.0f < (_hil_local_alt0 + 0.1f); // XXX improve?
+ if(hil_land_detector.landed != landed) {
+ hil_land_detector.landed = landed;
+ hil_land_detector.timestamp = hrt_absolute_time();
+
+ if (_land_detector_pub < 0) {
+ _land_detector_pub = orb_advertise(ORB_ID(vehicle_land_detected), &hil_land_detector);
+
+ } else {
+ orb_publish(ORB_ID(vehicle_land_detected), _land_detector_pub, &hil_land_detector);
+ }
+ }
+ }
+
/* accelerometer */
{
struct accel_report accel;
@@ -1379,10 +1395,10 @@ MavlinkReceiver::handle_message_hil_state_quaternion(mavlink_message_t *msg)
accel.temperature = 25.0f;
if (_accel_pub < 0) {
- _accel_pub = orb_advertise(ORB_ID(sensor_accel0), &accel);
+ _accel_pub = orb_advertise(ORB_ID(sensor_accel), &accel);
} else {
- orb_publish(ORB_ID(sensor_accel0), _accel_pub, &accel);
+ orb_publish(ORB_ID(sensor_accel), _accel_pub, &accel);
}
}