Skip to content

Commit 0b705c6

Browse files
Thomas StastnyJaeyoung-Lim
authored andcommitted
mavlink: add npfg_status, regenerate headers
1 parent d240ee9 commit 0b705c6

File tree

5 files changed

+106
-2
lines changed

5 files changed

+106
-2
lines changed

src/modules/fw_pos_control_l1/FixedwingPositionControl.cpp

Lines changed: 2 additions & 0 deletions
Original file line numberDiff line numberDiff line change
@@ -515,6 +515,8 @@ FixedwingPositionControl::status_publish()
515515
npfg_status.time_const = 0.0f;
516516
}
517517

518+
npfg_status.timestamp = hrt_absolute_time();
519+
518520
_pos_ctrl_status_pub.publish(pos_ctrl_status);
519521
_npfg_status_pub.publish(npfg_status);
520522
}

src/modules/mavlink/mavlink_main.cpp

Lines changed: 3 additions & 0 deletions
Original file line numberDiff line numberDiff line change
@@ -1528,6 +1528,7 @@ Mavlink::configure_streams_to_default(const char *configure_single_stream)
15281528
configure_stream_local("HOME_POSITION", 0.5f);
15291529
configure_stream_local("LOCAL_POSITION_NED", 1.0f);
15301530
configure_stream_local("NAV_CONTROLLER_OUTPUT", 1.0f);
1531+
configure_stream_local("NPFG_STATUS", 1.0f);
15311532
configure_stream_local("OBSTACLE_DISTANCE", 1.0f);
15321533
configure_stream_local("ORBIT_EXECUTION_STATUS", 2.0f);
15331534
configure_stream_local("PING", 0.1f);
@@ -1587,6 +1588,7 @@ Mavlink::configure_streams_to_default(const char *configure_single_stream)
15871588
configure_stream_local("GPS_STATUS", 1.0f);
15881589
configure_stream_local("HOME_POSITION", 0.5f);
15891590
configure_stream_local("NAV_CONTROLLER_OUTPUT", 10.0f);
1591+
configure_stream_local("NPFG_STATUS", 10.0f);
15901592
configure_stream_local("OPTICAL_FLOW_RAD", 10.0f);
15911593
configure_stream_local("ORBIT_EXECUTION_STATUS", 5.0f);
15921594
configure_stream_local("PING", 1.0f);
@@ -1729,6 +1731,7 @@ Mavlink::configure_streams_to_default(const char *configure_single_stream)
17291731
configure_stream_local("HOME_POSITION", 0.5f);
17301732
configure_stream_local("MANUAL_CONTROL", 5.0f);
17311733
configure_stream_local("NAV_CONTROLLER_OUTPUT", 10.0f);
1734+
configure_stream_local("NPFG_STATUS", 10.0f);
17321735
configure_stream_local("OPTICAL_FLOW_RAD", 10.0f);
17331736
configure_stream_local("ORBIT_EXECUTION_STATUS", 5.0f);
17341737
configure_stream_local("PING", 1.0f);

src/modules/mavlink/mavlink_messages.cpp

Lines changed: 5 additions & 1 deletion
Original file line numberDiff line numberDiff line change
@@ -88,6 +88,7 @@
8888
#include "streams/MANUAL_CONTROL.hpp"
8989
#include "streams/MOUNT_ORIENTATION.hpp"
9090
#include "streams/NAV_CONTROLLER_OUTPUT.hpp"
91+
#include "streams/NPFG_STATUS.hpp"
9192
#include "streams/OBSTACLE_DISTANCE.hpp"
9293
#include "streams/OPTICAL_FLOW_RAD.hpp"
9394
#include "streams/ORBIT_EXECUTION_STATUS.hpp"
@@ -533,8 +534,11 @@ static const StreamListItem streams_list[] = {
533534
create_stream_list_item<MavlinkStreamComponentInformation>(),
534535
#endif // COMPONENT_INFORMATION_HPP
535536
#if defined(RAW_RPM_HPP)
536-
create_stream_list_item<MavlinkStreamRawRpm>()
537+
create_stream_list_item<MavlinkStreamRawRpm>(),
537538
#endif // RAW_RPM_HPP
539+
#if defined(NPFG_STATUS_HPP)
540+
create_stream_list_item<MavlinkStreamNPFGStatus>()
541+
#endif // NPFG_STATUS
538542
};
539543

540544
const char *get_stream_name(const uint16_t msg_id)
Lines changed: 95 additions & 0 deletions
Original file line numberDiff line numberDiff line change
@@ -0,0 +1,95 @@
1+
/****************************************************************************
2+
*
3+
* Copyright (c) 2021 Autonomous Systems Lab, ETH Zurich. All rights reserved.
4+
*
5+
* Redistribution and use in source and binary forms, with or without
6+
* modification, are permitted provided that the following conditions
7+
* are met:
8+
*
9+
* 1. Redistributions of source code must retain the above copyright
10+
* notice, this list of conditions and the following disclaimer.
11+
* 2. Redistributions in binary form must reproduce the above copyright
12+
* notice, this list of conditions and the following disclaimer in
13+
* the documentation and/or other materials provided with the
14+
* distribution.
15+
* 3. Neither the name PX4 nor the names of its contributors may be
16+
* used to endorse or promote products derived from this software
17+
* without specific prior written permission.
18+
*
19+
* THIS SOFTWARE IS PROVIDED BY THE COPYRIGHT HOLDERS AND CONTRIBUTORS
20+
* "AS IS" AND ANY EXPRESS OR IMPLIED WARRANTIES, INCLUDING, BUT NOT
21+
* LIMITED TO, THE IMPLIED WARRANTIES OF MERCHANTABILITY AND FITNESS
22+
* FOR A PARTICULAR PURPOSE ARE DISCLAIMED. IN NO EVENT SHALL THE
23+
* COPYRIGHT OWNER OR CONTRIBUTORS BE LIABLE FOR ANY DIRECT, INDIRECT,
24+
* INCIDENTAL, SPECIAL, EXEMPLARY, OR CONSEQUENTIAL DAMAGES (INCLUDING,
25+
* BUT NOT LIMITED TO, PROCUREMENT OF SUBSTITUTE GOODS OR SERVICES; LOSS
26+
* OF USE, DATA, OR PROFITS; OR BUSINESS INTERRUPTION) HOWEVER CAUSED
27+
* AND ON ANY THEORY OF LIABILITY, WHETHER IN CONTRACT, STRICT
28+
* LIABILITY, OR TORT (INCLUDING NEGLIGENCE OR OTHERWISE) ARISING IN
29+
* ANY WAY OUT OF THE USE OF THIS SOFTWARE, EVEN IF ADVISED OF THE
30+
* POSSIBILITY OF SUCH DAMAGE.
31+
*
32+
****************************************************************************/
33+
34+
#ifndef NPFG_STATUS_HPP
35+
#define NPFG_STATUS_HPP
36+
37+
#include <uORB/topics/npfg_status.h>
38+
39+
class MavlinkStreamNPFGStatus : public MavlinkStream
40+
{
41+
public:
42+
static MavlinkStream *new_instance(Mavlink *mavlink) { return new MavlinkStreamNPFGStatus(mavlink); }
43+
44+
static constexpr const char *get_name_static() { return "NPFG_STATUS"; }
45+
static constexpr uint16_t get_id_static() { return MAVLINK_MSG_ID_NPFG_STATUS; }
46+
47+
const char *get_name() const override { return get_name_static(); }
48+
uint16_t get_id() override { return get_id_static(); }
49+
50+
unsigned get_size() override
51+
{
52+
if (_npfg_status_sub.advertised()) {
53+
return MAVLINK_MSG_ID_NPFG_STATUS_LEN + MAVLINK_NUM_NON_PAYLOAD_BYTES;
54+
}
55+
56+
return 0;
57+
}
58+
59+
private:
60+
explicit MavlinkStreamNPFGStatus(Mavlink *mavlink) : MavlinkStream(mavlink) {}
61+
62+
uORB::Subscription _npfg_status_sub{ORB_ID(npfg_status)};
63+
64+
bool send() override
65+
{
66+
struct npfg_status_s npfg_status;
67+
68+
if (_npfg_status_sub.update(&npfg_status)) {
69+
mavlink_npfg_status_t msg{};
70+
71+
msg.timestamp = npfg_status.timestamp;
72+
msg.lat_accel = npfg_status.lat_accel;
73+
msg.lat_accel_ff = npfg_status.lat_accel_ff;
74+
msg.bearing_feas = npfg_status.bearing_feas;
75+
msg.bearing_feas_on_track = npfg_status.bearing_feas_on_track;
76+
msg.signed_track_error = npfg_status.signed_track_error;
77+
msg.track_error_bound = npfg_status.track_error_bound;
78+
msg.airspeed_ref = npfg_status.airspeed_ref;
79+
msg.bearing = math::degrees(npfg_status.bearing);
80+
msg.heading_ref = math::degrees(npfg_status.heading_ref);
81+
msg.min_ground_speed_ref = npfg_status.min_ground_speed_ref;
82+
msg.adapted_period = npfg_status.adapted_period;
83+
msg.p_gain = npfg_status.p_gain;
84+
msg.time_const = npfg_status.time_const;
85+
86+
mavlink_msg_npfg_status_send_struct(_mavlink->get_channel(), &msg);
87+
88+
return true;
89+
}
90+
91+
return false;
92+
}
93+
};
94+
95+
#endif // NPFG_STATUS

0 commit comments

Comments
 (0)