update mavlink to master, rename MOUNT_STATUS

The mavlink message MOUNT_STATUS has been renamed to MOUNT_ORIENTATION.

This changes the Firmware code accordingly.
This commit is contained in:
Julian Oes 2016-11-28 18:48:09 +01:00 committed by Lorenz Meier
parent 780e903d5b
commit 0109f6f549
7 changed files with 31 additions and 31 deletions

@ -1 +1 @@
Subproject commit d6e317e1ca97bf4ac4a6d1d4e8eb1fd85b7c7a1a Subproject commit fb57c62ee8b14c86f423d1549a90e0f6879584dc

@ -1 +1 @@
Subproject commit 714eab3a4ffadd09e86f8e56a31a17237ad35a08 Subproject commit 10d730a446995b989e88ee15f14d9c28a3a428cc

View File

@ -122,7 +122,7 @@ set(msg_file_names
vtol_vehicle_status.msg vtol_vehicle_status.msg
wind_estimate.msg wind_estimate.msg
vehicle_roi.msg vehicle_roi.msg
mount_status.msg mount_orientation.msg
collision_report.msg collision_report.msg
) )

View File

@ -44,7 +44,7 @@
#include <uORB/topics/vehicle_attitude.h> #include <uORB/topics/vehicle_attitude.h>
#include <uORB/topics/vehicle_attitude.h> #include <uORB/topics/vehicle_attitude.h>
#include <uORB/topics/vehicle_global_position.h> #include <uORB/topics/vehicle_global_position.h>
#include <uORB/topics/mount_status.h> #include <uORB/topics/mount_orientation.h>
#include <px4_defines.h> #include <px4_defines.h>
#include <geo/geo.h> #include <geo/geo.h>
#include <math.h> #include <math.h>
@ -86,13 +86,13 @@ int OutputBase::initialize()
void OutputBase::publish() void OutputBase::publish()
{ {
int instance; int instance;
mount_status_s mount_status; mount_orientation_s mount_orientation;
for (unsigned i = 0; i < 3; ++i) { for (unsigned i = 0; i < 3; ++i) {
mount_status.attitude_euler_angle[i] = _angle_outputs[i]; mount_orientation.attitude_euler_angle[i] = _angle_outputs[i];
} }
orb_publish_auto(ORB_ID(mount_status), &_mount_status_pub, &mount_status, &instance, ORB_PRIO_DEFAULT); orb_publish_auto(ORB_ID(mount_orientation), &_mount_orientation_pub, &mount_orientation, &instance, ORB_PRIO_DEFAULT);
} }
float OutputBase::_calculate_pitch(double lon, double lat, float altitude, float OutputBase::_calculate_pitch(double lon, double lat, float altitude,

View File

@ -80,7 +80,7 @@ public:
/** report status to stdout */ /** report status to stdout */
virtual void print_status() = 0; virtual void print_status() = 0;
/** Publish _angle_outputs as a mount_status message. */ /** Publish _angle_outputs as a mount_orientation message. */
void publish(); void publish();
protected: protected:
@ -114,7 +114,7 @@ private:
int _vehicle_attitude_sub = -1; int _vehicle_attitude_sub = -1;
int _vehicle_global_position_sub = -1; int _vehicle_global_position_sub = -1;
orb_advert_t _mount_status_pub = nullptr; orb_advert_t _mount_orientation_pub = nullptr;
}; };

View File

@ -89,7 +89,7 @@
#include <uORB/topics/vision_position_estimate.h> #include <uORB/topics/vision_position_estimate.h>
#include <uORB/topics/vtol_vehicle_status.h> #include <uORB/topics/vtol_vehicle_status.h>
#include <uORB/topics/wind_estimate.h> #include <uORB/topics/wind_estimate.h>
#include <uORB/topics/mount_status.h> #include <uORB/topics/mount_orientation.h>
#include <uORB/topics/collision_report.h> #include <uORB/topics/collision_report.h>
#include <uORB/uORB.h> #include <uORB/uORB.h>
@ -3526,22 +3526,22 @@ protected:
} }
}; };
class MavlinkStreamMountStatus : public MavlinkStream class MavlinkStreamMountOrientation : public MavlinkStream
{ {
public: public:
const char *get_name() const const char *get_name() const
{ {
return MavlinkStreamMountStatus::get_name_static(); return MavlinkStreamMountOrientation::get_name_static();
} }
static const char *get_name_static() static const char *get_name_static()
{ {
return "MOUNT_STATUS"; return "MOUNT_ORIENTATION";
} }
static uint16_t get_id_static() static uint16_t get_id_static()
{ {
return MAVLINK_MSG_ID_MOUNT_STATUS; return MAVLINK_MSG_ID_MOUNT_ORIENTATION;
} }
uint16_t get_id() uint16_t get_id()
@ -3551,43 +3551,43 @@ public:
static MavlinkStream *new_instance(Mavlink *mavlink) static MavlinkStream *new_instance(Mavlink *mavlink)
{ {
return new MavlinkStreamMountStatus(mavlink); return new MavlinkStreamMountOrientation(mavlink);
} }
unsigned get_size() unsigned get_size()
{ {
return (_mount_status_time > 0) ? MAVLINK_MSG_ID_MOUNT_STATUS_LEN + MAVLINK_NUM_NON_PAYLOAD_BYTES : 0; return (_mount_orientation_time > 0) ? MAVLINK_MSG_ID_MOUNT_ORIENTATION_LEN + MAVLINK_NUM_NON_PAYLOAD_BYTES : 0;
} }
private: private:
MavlinkOrbSubscription *_mount_status_sub; MavlinkOrbSubscription *_mount_orientation_sub;
uint64_t _mount_status_time; uint64_t _mount_orientation_time;
/* do not allow top copying this class */ /* do not allow top copying this class */
MavlinkStreamMountStatus(MavlinkStreamMountStatus &); MavlinkStreamMountOrientation(MavlinkStreamMountOrientation &);
MavlinkStreamMountStatus &operator = (const MavlinkStreamMountStatus &); MavlinkStreamMountOrientation &operator = (const MavlinkStreamMountOrientation &);
protected: protected:
explicit MavlinkStreamMountStatus(Mavlink *mavlink) : MavlinkStream(mavlink), explicit MavlinkStreamMountOrientation(Mavlink *mavlink) : MavlinkStream(mavlink),
_mount_status_sub(_mavlink->add_orb_subscription(ORB_ID(mount_status))), _mount_orientation_sub(_mavlink->add_orb_subscription(ORB_ID(mount_orientation))),
_mount_status_time(0) _mount_orientation_time(0)
{} {}
void send(const hrt_abstime t) void send(const hrt_abstime t)
{ {
struct mount_status_s mount_status = {}; struct mount_orientation_s mount_orientation = {};
bool updated = _mount_status_sub->update(&_mount_status_time, &mount_status); bool updated = _mount_orientation_sub->update(&_mount_orientation_time, &mount_orientation);
if (updated) { if (updated) {
mavlink_mount_status_t msg = {}; mavlink_mount_orientation_t msg = {};
msg.roll = 180.0f / M_PI_F * mount_status.attitude_euler_angle[0]; msg.roll = 180.0f / M_PI_F * mount_orientation.attitude_euler_angle[0];
msg.pitch = 180.0f / M_PI_F * mount_status.attitude_euler_angle[1]; msg.pitch = 180.0f / M_PI_F * mount_orientation.attitude_euler_angle[1];
msg.yaw = 180.0f / M_PI_F * mount_status.attitude_euler_angle[2]; msg.yaw = 180.0f / M_PI_F * mount_orientation.attitude_euler_angle[2];
mavlink_msg_mount_status_send_struct(_mavlink->get_channel(), &msg); mavlink_msg_mount_orientation_send_struct(_mavlink->get_channel(), &msg);
} }
} }
}; };
@ -3637,6 +3637,6 @@ const StreamListItem *streams_list[] = {
new StreamListItem(&MavlinkStreamADSBVehicle::new_instance, &MavlinkStreamADSBVehicle::get_name_static, &MavlinkStreamADSBVehicle::get_id_static), new StreamListItem(&MavlinkStreamADSBVehicle::new_instance, &MavlinkStreamADSBVehicle::get_name_static, &MavlinkStreamADSBVehicle::get_id_static),
new StreamListItem(&MavlinkStreamCollision::new_instance, &MavlinkStreamCollision::get_name_static, &MavlinkStreamCollision::get_id_static), new StreamListItem(&MavlinkStreamCollision::new_instance, &MavlinkStreamCollision::get_name_static, &MavlinkStreamCollision::get_id_static),
new StreamListItem(&MavlinkStreamWind::new_instance, &MavlinkStreamWind::get_name_static, &MavlinkStreamWind::get_id_static), new StreamListItem(&MavlinkStreamWind::new_instance, &MavlinkStreamWind::get_name_static, &MavlinkStreamWind::get_id_static),
new StreamListItem(&MavlinkStreamMountStatus::new_instance, &MavlinkStreamMountStatus::get_name_static, &MavlinkStreamMountStatus::get_id_static), new StreamListItem(&MavlinkStreamMountOrientation::new_instance, &MavlinkStreamMountOrientation::get_name_static, &MavlinkStreamMountOrientation::get_id_static),
nullptr nullptr
}; };