aboutsummaryrefslogtreecommitdiff
path: root/src/modules/mavlink
diff options
context:
space:
mode:
authorThomas Gubler <thomasgubler@gmail.com>2015-02-01 11:06:47 +0100
committerThomas Gubler <thomasgubler@gmail.com>2015-02-01 11:06:47 +0100
commit84ff3c671d5c6d00a1b6c9a8062bddfb6875f8f9 (patch)
treedb0470a2471776e9ffe525b2fa7302cec7ab8bd8 /src/modules/mavlink
parent7c958a2cca90a6262dc491fe9ef86d85bacdf3da (diff)
parenta2a244584e36a0e9ffdb93a0dda8473baf8344d3 (diff)
downloadpx4-firmware-84ff3c671d5c6d00a1b6c9a8062bddfb6875f8f9.tar.gz
px4-firmware-84ff3c671d5c6d00a1b6c9a8062bddfb6875f8f9.tar.bz2
px4-firmware-84ff3c671d5c6d00a1b6c9a8062bddfb6875f8f9.zip
Merge remote-tracking branch 'upstream/master' into ros_messagelayer_merge2_attctrl_posctrl
Conflicts: src/drivers/px4fmu/fmu.cpp
Diffstat (limited to 'src/modules/mavlink')
-rw-r--r--src/modules/mavlink/mavlink_main.cpp6
-rw-r--r--src/modules/mavlink/mavlink_main.h2
-rw-r--r--src/modules/mavlink/mavlink_messages.cpp11
-rw-r--r--src/modules/mavlink/mavlink_orb_subscription.cpp11
-rw-r--r--src/modules/mavlink/mavlink_orb_subscription.h4
-rw-r--r--src/modules/mavlink/mavlink_receiver.cpp21
6 files changed, 29 insertions, 26 deletions
diff --git a/src/modules/mavlink/mavlink_main.cpp b/src/modules/mavlink/mavlink_main.cpp
index 676b65adc..6bd0c7bce 100644
--- a/src/modules/mavlink/mavlink_main.cpp
+++ b/src/modules/mavlink/mavlink_main.cpp
@@ -904,20 +904,20 @@ Mavlink::send_statustext(unsigned char severity, const char *string)
mavlink_logbuffer_write(&_logbuffer, &logmsg);
}
-MavlinkOrbSubscription *Mavlink::add_orb_subscription(const orb_id_t topic)
+MavlinkOrbSubscription *Mavlink::add_orb_subscription(const orb_id_t topic, int instance)
{
/* check if already subscribed to this topic */
MavlinkOrbSubscription *sub;
LL_FOREACH(_subscriptions, sub) {
- if (sub->get_topic() == topic) {
+ if (sub->get_topic() == topic && sub->get_instance() == instance) {
/* already subscribed */
return sub;
}
}
/* add new subscription */
- MavlinkOrbSubscription *sub_new = new MavlinkOrbSubscription(topic);
+ MavlinkOrbSubscription *sub_new = new MavlinkOrbSubscription(topic, instance);
LL_APPEND(_subscriptions, sub_new);
diff --git a/src/modules/mavlink/mavlink_main.h b/src/modules/mavlink/mavlink_main.h
index ad5e5001b..baaa7bc13 100644
--- a/src/modules/mavlink/mavlink_main.h
+++ b/src/modules/mavlink/mavlink_main.h
@@ -171,7 +171,7 @@ public:
void handle_message(const mavlink_message_t *msg);
- MavlinkOrbSubscription *add_orb_subscription(const orb_id_t topic);
+ MavlinkOrbSubscription *add_orb_subscription(const orb_id_t topic, int instance=0);
int get_instance_id();
diff --git a/src/modules/mavlink/mavlink_messages.cpp b/src/modules/mavlink/mavlink_messages.cpp
index 6642fb2ac..be7d91c65 100644
--- a/src/modules/mavlink/mavlink_messages.cpp
+++ b/src/modules/mavlink/mavlink_messages.cpp
@@ -1342,14 +1342,7 @@ protected:
_act_sub(nullptr),
_act_time(0)
{
- orb_id_t act_topics[] = {
- ORB_ID(actuator_outputs_0),
- ORB_ID(actuator_outputs_1),
- ORB_ID(actuator_outputs_2),
- ORB_ID(actuator_outputs_3)
- };
-
- _act_sub = _mavlink->add_orb_subscription(act_topics[N]);
+ _act_sub = _mavlink->add_orb_subscription(ORB_ID(actuator_outputs), N);
}
void send(const hrt_abstime t)
@@ -1424,7 +1417,7 @@ protected:
_status_time(0),
_pos_sp_triplet_sub(_mavlink->add_orb_subscription(ORB_ID(position_setpoint_triplet))),
_pos_sp_triplet_time(0),
- _act_sub(_mavlink->add_orb_subscription(ORB_ID(actuator_outputs_0))),
+ _act_sub(_mavlink->add_orb_subscription(ORB_ID(actuator_outputs))),
_act_time(0)
{}
diff --git a/src/modules/mavlink/mavlink_orb_subscription.cpp b/src/modules/mavlink/mavlink_orb_subscription.cpp
index 734f0903a..315776e29 100644
--- a/src/modules/mavlink/mavlink_orb_subscription.cpp
+++ b/src/modules/mavlink/mavlink_orb_subscription.cpp
@@ -46,10 +46,11 @@
#include "mavlink_orb_subscription.h"
-MavlinkOrbSubscription::MavlinkOrbSubscription(const orb_id_t topic) :
+MavlinkOrbSubscription::MavlinkOrbSubscription(const orb_id_t topic, int instance) :
next(nullptr),
_topic(topic),
- _fd(orb_subscribe(_topic)),
+ _instance(instance),
+ _fd(orb_subscribe_multi(_topic, instance)),
_published(false)
{
}
@@ -65,6 +66,12 @@ MavlinkOrbSubscription::get_topic() const
return _topic;
}
+int
+MavlinkOrbSubscription::get_instance() const
+{
+ return _instance;
+}
+
bool
MavlinkOrbSubscription::update(uint64_t *time, void* data)
{
diff --git a/src/modules/mavlink/mavlink_orb_subscription.h b/src/modules/mavlink/mavlink_orb_subscription.h
index 7af454df6..5394e5097 100644
--- a/src/modules/mavlink/mavlink_orb_subscription.h
+++ b/src/modules/mavlink/mavlink_orb_subscription.h
@@ -50,7 +50,7 @@ class MavlinkOrbSubscription
public:
MavlinkOrbSubscription *next; ///< pointer to next subscription in list
- MavlinkOrbSubscription(const orb_id_t topic);
+ MavlinkOrbSubscription(const orb_id_t topic, int instance);
~MavlinkOrbSubscription();
/**
@@ -77,9 +77,11 @@ public:
*/
bool is_published();
orb_id_t get_topic() const;
+ int get_instance() const;
private:
const orb_id_t _topic; ///< topic metadata
+ const int _instance; ///< get topic instance
int _fd; ///< subscription handle
bool _published; ///< topic was ever published
diff --git a/src/modules/mavlink/mavlink_receiver.cpp b/src/modules/mavlink/mavlink_receiver.cpp
index b1ba91cac..4d7b35f03 100644
--- a/src/modules/mavlink/mavlink_receiver.cpp
+++ b/src/modules/mavlink/mavlink_receiver.cpp
@@ -1043,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);
}
}
@@ -1065,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);
}
}
@@ -1086,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);
}
}
@@ -1104,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);
}
}
@@ -1394,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);
}
}