aboutsummaryrefslogtreecommitdiff
path: root/src/platforms
diff options
context:
space:
mode:
authorThomas Gubler <thomasgubler@gmail.com>2015-01-02 09:08:49 +0100
committerThomas Gubler <thomasgubler@gmail.com>2015-01-02 09:09:20 +0100
commit92729b3020afe204aebaeb14d502654ad9251e45 (patch)
tree9571dfeb332c13d953e96676452faf615dbfb895 /src/platforms
parent9586a8f5b11314380f1e07ef6a09bff3c430c7e6 (diff)
downloadpx4-firmware-92729b3020afe204aebaeb14d502654ad9251e45.tar.gz
px4-firmware-92729b3020afe204aebaeb14d502654ad9251e45.tar.bz2
px4-firmware-92729b3020afe204aebaeb14d502654ad9251e45.zip
commander dummy node: publish param update at low freq to make other nodes update their params
Diffstat (limited to 'src/platforms')
-rw-r--r--src/platforms/ros/nodes/commander/commander.cpp10
-rw-r--r--src/platforms/ros/nodes/commander/commander.h4
2 files changed, 13 insertions, 1 deletions
diff --git a/src/platforms/ros/nodes/commander/commander.cpp b/src/platforms/ros/nodes/commander/commander.cpp
index f767bbb36..1972d8cfa 100644
--- a/src/platforms/ros/nodes/commander/commander.cpp
+++ b/src/platforms/ros/nodes/commander/commander.cpp
@@ -51,7 +51,9 @@ Commander::Commander() :
_man_ctrl_sp_sub(_n.subscribe("manual_control_setpoint", 10, &Commander::ManualControlInputCallback, this)),
_vehicle_control_mode_pub(_n.advertise<px4::vehicle_control_mode>("vehicle_control_mode", 10)),
_actuator_armed_pub(_n.advertise<px4::actuator_armed>("actuator_armed", 10)),
- _vehicle_status_pub(_n.advertise<px4::vehicle_status>("vehicle_status", 10))
+ _vehicle_status_pub(_n.advertise<px4::vehicle_status>("vehicle_status", 10)),
+ _parameter_update_pub(_n.advertise<px4::parameter_update>("parameter_update", 10)),
+ _msg_parameter_update()
{
}
@@ -85,6 +87,12 @@ void Commander::ManualControlInputCallback(const px4::manual_control_setpointCon
_vehicle_control_mode_pub.publish(msg_vehicle_control_mode);
_actuator_armed_pub.publish(msg_actuator_armed);
_vehicle_status_pub.publish(msg_vehicle_status);
+
+ /* Fill parameter update */
+ if (px4::get_time_micros() - _msg_parameter_update.timestamp > 1e6) {
+ _msg_parameter_update.timestamp = px4::get_time_micros();
+ _parameter_update_pub.publish(_msg_parameter_update);
+ }
}
int main(int argc, char **argv)
diff --git a/src/platforms/ros/nodes/commander/commander.h b/src/platforms/ros/nodes/commander/commander.h
index d7fe0a4ca..cd9be5135 100644
--- a/src/platforms/ros/nodes/commander/commander.h
+++ b/src/platforms/ros/nodes/commander/commander.h
@@ -40,6 +40,7 @@
#include "ros/ros.h"
#include <px4/manual_control_setpoint.h>
+#include <px4/parameter_update.h>
class Commander {
public:
@@ -58,5 +59,8 @@ protected:
ros::Publisher _vehicle_control_mode_pub;
ros::Publisher _actuator_armed_pub;
ros::Publisher _vehicle_status_pub;
+ ros::Publisher _parameter_update_pub;
+
+ px4::parameter_update _msg_parameter_update;
};