diff options
author | Thomas Gubler <thomasgubler@gmail.com> | 2015-02-28 18:15:51 +0100 |
---|---|---|
committer | Thomas Gubler <thomasgubler@gmail.com> | 2015-03-10 20:56:53 +0100 |
commit | c07c39bc438695101dc58d2fda2e14914e019ca4 (patch) | |
tree | 1bfd6e649b721dd896952308f2a999cfb08e4788 /src | |
parent | 1837440e4336fda1462de24d622d200d67471ac5 (diff) | |
download | px4-firmware-c07c39bc438695101dc58d2fda2e14914e019ca4.tar.gz px4-firmware-c07c39bc438695101dc58d2fda2e14914e019ca4.tar.bz2 px4-firmware-c07c39bc438695101dc58d2fda2e14914e019ca4.zip |
update ros launch files and nodes for update of rotors_simulator
Diffstat (limited to 'src')
-rw-r--r-- | src/platforms/ros/nodes/mc_mixer/mc_mixer.cpp | 6 |
1 files changed, 3 insertions, 3 deletions
diff --git a/src/platforms/ros/nodes/mc_mixer/mc_mixer.cpp b/src/platforms/ros/nodes/mc_mixer/mc_mixer.cpp index 1098ec73b..9b48294b6 100644 --- a/src/platforms/ros/nodes/mc_mixer/mc_mixer.cpp +++ b/src/platforms/ros/nodes/mc_mixer/mc_mixer.cpp @@ -40,7 +40,7 @@ #include <ros/ros.h> #include <px4.h> #include <lib/mathlib/mathlib.h> -#include <mav_msgs/MotorSpeed.h> +#include <mav_msgs/CommandMotorSpeed.h> #include <string> class MultirotorMixer @@ -129,7 +129,7 @@ MultirotorMixer::MultirotorMixer(): _rotors(_config_index[0]) { _sub = _n.subscribe("actuator_controls_0", 1, &MultirotorMixer::actuatorControlsCallback, this); - _pub = _n.advertise<mav_msgs::MotorSpeed>("/mixed_motor_commands", 10); + _pub = _n.advertise<mav_msgs::CommandMotorSpeed>("command/motor_speed", 10); if (!_n.hasParam("motor_scaling_radps")) { _n.setParam("motor_scaling_radps", 150.0); @@ -237,7 +237,7 @@ void MultirotorMixer::actuatorControlsCallback(const px4::actuator_controls_0 &m mix(); // publish message - mav_msgs::MotorSpeed rotor_vel_msg; + mav_msgs::CommandMotorSpeed rotor_vel_msg; double scaling; double offset; _n.getParamCached("motor_scaling_radps", scaling); |