Skip to content

Commit c023003

Browse files
committed
plugins: port sys_time
1 parent 4808f47 commit c023003

File tree

6 files changed

+197
-128
lines changed

6 files changed

+197
-128
lines changed

cog-requirements.txt

+4
Original file line numberDiff line numberDiff line change
@@ -0,0 +1,4 @@
1+
attrs
2+
comment_parser
3+
cogapp
4+
# pymavlink

mavros/CMakeLists.txt

+1-1
Original file line numberDiff line numberDiff line change
@@ -133,7 +133,7 @@ add_library(mavros_plugins SHARED
133133
#src/plugins/setpoint_trajectory.cpp
134134
#src/plugins/setpoint_velocity.cpp
135135
src/plugins/sys_status.cpp
136-
#src/plugins/sys_time.cpp
136+
src/plugins/sys_time.cpp
137137
#src/plugins/vfr_hud.cpp
138138
#src/plugins/waypoint.cpp
139139
#src/plugins/wind_estimation.cpp

mavros/include/mavros/plugin.hpp

+5
Original file line numberDiff line numberDiff line change
@@ -99,6 +99,11 @@ class Plugin : public std::enable_shared_from_this<Plugin>
9999
return node->get_logger();
100100
}
101101

102+
virtual rclcpp::Clock::SharedPtr get_clock() const
103+
{
104+
return node->get_clock();
105+
}
106+
102107
protected:
103108
UASPtr uas; // uas back link
104109
rclcpp::Node::SharedPtr node; // most of plugins uses sub-node

mavros/mavros_plugins.xml

+5-1
Original file line numberDiff line numberDiff line change
@@ -17,5 +17,9 @@ Example and &quot;how to&quot; for users.</description>
1717

1818
Required by all plugins.</description>
1919
</class>
20+
<class name="sys_time" type="mavros::plugin::PluginFactoryTemplate&lt;mavros::std_plugins::SystemTimePlugin&gt;" base_class_type="mavros::plugin::PluginFactory">
21+
<description>@brief System time plugin
22+
@plugin sys_time</description>
23+
</class>
2024
</library>
21-
<!-- [[[end]]] (checksum: 35dc3ab809a88eee6f71ccebe9065842) -->
25+
<!-- [[[end]]] (checksum: 43ac52466bcdf3ccfa48f25dddd93fc8) -->

mavros/src/lib/enum_to_string.cpp

+14-7
Original file line numberDiff line numberDiff line change
@@ -208,7 +208,7 @@ std::string to_string(MAV_TYPE e)
208208

209209
return mav_type_strings[idx];
210210
}
211-
// [[[end]]] (checksum: b19fc361579ab1037668c7e31cc07457)
211+
// [[[end]]] (checksum: 2225b2c1f3e1e415ebfafe748dc0d8a9)
212212

213213
// [[[cog:
214214
// ename = 'MAV_TYPE'
@@ -264,7 +264,7 @@ std::string enum_to_name(MAV_TYPE e)
264264

265265
return mav_type_names[idx];
266266
}
267-
// [[[end]]] (checksum: df50c492bb4cbef1cbcf23d6945cdcf7)
267+
// [[[end]]] (checksum: 98203eae4520462308933422fb6c0fa5)
268268

269269
// [[[cog:
270270
// ename = 'MAV_STATE'
@@ -507,7 +507,7 @@ std::string to_string(MAV_MISSION_RESULT e)
507507

508508
return mav_mission_result_strings[idx];
509509
}
510-
// [[[end]]] (checksum: 74e4e9b086e55247dab312fcc33eace9)
510+
// [[[end]]] (checksum: d58f714b2b068a3be44ac1f2988ed44e)
511511

512512
// [[[cog:
513513
// ename = 'MAV_FRAME'
@@ -548,7 +548,7 @@ std::string to_string(MAV_FRAME e)
548548

549549
return mav_frame_strings[idx];
550550
}
551-
// [[[end]]] (checksum: 1edbc1b946bae08b05508893336208c0)
551+
// [[[end]]] (checksum: a08a81c88d8a8ae58c83a146541031fc)
552552

553553
// [[[cog:
554554
// ename = 'MAV_COMPONENT'
@@ -584,7 +584,7 @@ static const std::unordered_map<size_t, const std::string> mav_comp_id_strings{{
584584
{37, "USER13"}, // Id for a component on privately managed MAVLink network. Can be used for any purpose but may not be published by components outside of the private network.
585585
{38, "USER14"}, // Id for a component on privately managed MAVLink network. Can be used for any purpose but may not be published by components outside of the private network.
586586
{39, "USER15"}, // Id for a component on privately managed MAVLink network. Can be used for any purpose but may not be published by components outside of the private network.
587-
{40, "USE16"}, // Id for a component on privately managed MAVLink network. Can be used for any purpose but may not be published by components outside of the private network.
587+
{40, "USER16"}, // Id for a component on privately managed MAVLink network. Can be used for any purpose but may not be published by components outside of the private network.
588588
{41, "USER17"}, // Id for a component on privately managed MAVLink network. Can be used for any purpose but may not be published by components outside of the private network.
589589
{42, "USER18"}, // Id for a component on privately managed MAVLink network. Can be used for any purpose but may not be published by components outside of the private network.
590590
{43, "USER19"}, // Id for a component on privately managed MAVLink network. Can be used for any purpose but may not be published by components outside of the private network.
@@ -612,7 +612,7 @@ static const std::unordered_map<size_t, const std::string> mav_comp_id_strings{{
612612
{65, "USER41"}, // Id for a component on privately managed MAVLink network. Can be used for any purpose but may not be published by components outside of the private network.
613613
{66, "USER42"}, // Id for a component on privately managed MAVLink network. Can be used for any purpose but may not be published by components outside of the private network.
614614
{67, "USER43"}, // Id for a component on privately managed MAVLink network. Can be used for any purpose but may not be published by components outside of the private network.
615-
{68, "USER44"}, // Id for a component on privately managed MAVLink network. Can be used for any purpose but may not be published by components outside of the private network.
615+
{68, "TELEMETRY_RADIO"}, // Telemetry radio (e.g. SiK radio, or other component that emits RADIO_STATUS messages).
616616
{69, "USER45"}, // Id for a component on privately managed MAVLink network. Can be used for any purpose but may not be published by components outside of the private network.
617617
{70, "USER46"}, // Id for a component on privately managed MAVLink network. Can be used for any purpose but may not be published by components outside of the private network.
618618
{71, "USER47"}, // Id for a component on privately managed MAVLink network. Can be used for any purpose but may not be published by components outside of the private network.
@@ -676,7 +676,10 @@ static const std::unordered_map<size_t, const std::string> mav_comp_id_strings{{
676676
{173, "GIMBAL4"}, // Gimbal #4
677677
{174, "GIMBAL5"}, // Gimbal #5.
678678
{175, "GIMBAL6"}, // Gimbal #6.
679+
{180, "BATTERY"}, // Battery #1.
680+
{181, "BATTERY2"}, // Battery #2.
679681
{190, "MISSIONPLANNER"}, // Component that can generate/supply a mission flight plan (e.g. GCS or developer API).
682+
{191, "ONBOARD_COMPUTER"}, // Component that lives on the onboard computer (companion computer) and has some generic functionalities, such as settings system parameters and monitoring the status of some processes that don't directly speak mavlink and so on.
680683
{195, "PATHPLANNER"}, // Component that finds an optimal path between points based on a certain constraint (e.g. minimum snap, shortest path, cost, etc.).
681684
{196, "OBSTACLE_AVOIDANCE"}, // Component that plans a collision free path between two points.
682685
{197, "VISUAL_INERTIAL_ODOMETRY"}, // Component that provides position estimates using VIO techniques.
@@ -686,11 +689,15 @@ static const std::unordered_map<size_t, const std::string> mav_comp_id_strings{{
686689
{202, "IMU_3"}, // Inertial Measurement Unit (IMU) #3.
687690
{220, "GPS"}, // GPS #1.
688691
{221, "GPS2"}, // GPS #2.
692+
{236, "ODID_TXRX_1"}, // Open Drone ID transmitter/receiver (Bluetooth/WiFi/Internet).
693+
{237, "ODID_TXRX_2"}, // Open Drone ID transmitter/receiver (Bluetooth/WiFi/Internet).
694+
{238, "ODID_TXRX_3"}, // Open Drone ID transmitter/receiver (Bluetooth/WiFi/Internet).
689695
{240, "UDP_BRIDGE"}, // Component to bridge MAVLink to UDP (i.e. from a UART).
690696
{241, "UART_BRIDGE"}, // Component to bridge to UART (i.e. from UDP).
697+
{242, "TUNNEL_NODE"}, // Component handling TUNNEL messages (e.g. vendor specific GUI of a component).
691698
{250, "SYSTEM_CONTROL"}, // Component for handling system messages (e.g. to ARM, takeoff, etc.).
692699
}};
693-
// [[[end]]] (checksum: 0e9b67b8bf172339bcf2778c576110fe)
700+
// [[[end]]] (checksum: aad4a6e160b5719494a6ede65e5f244a)
694701

695702
std::string to_string(MAV_COMPONENT e)
696703
{

0 commit comments

Comments
 (0)