Browse Source

ros: make mixer name a param

sbg
Thomas Gubler 10 years ago
parent
commit
6b0d0aa2a5
  1. 2
      launch/gazebo_ardrone_empty_world.launch
  2. 2
      launch/gazebo_ardrone_house_world.launch
  3. 2
      launch/gazebo_iris_empty_world.launch
  4. 2
      launch/gazebo_iris_outdoor_world.launch
  5. 1
      launch/multicopter.launch
  6. 9
      launch/multicopter_w.launch
  7. 9
      launch/multicopter_x.launch
  8. 20
      src/platforms/ros/nodes/mc_mixer/mc_mixer.cpp

2
launch/gazebo_ardrone_empty_world.launch

@ -1,6 +1,6 @@ @@ -1,6 +1,6 @@
<launch>
<include file="$(find mav_gazebo)/launch/ardrone_empty_world_with_joy.launch" />
<include file="$(find px4)/launch/multicopter.launch" />
<include file="$(find px4)/launch/multicopter_x.launch" />
</launch>

2
launch/gazebo_ardrone_house_world.launch

@ -1,6 +1,6 @@ @@ -1,6 +1,6 @@
<launch>
<include file="$(find mav_gazebo)/launch/ardrone_house_world_with_joy.launch" />
<include file="$(find px4)/launch/multicopter.launch" />
<include file="$(find px4)/launch/multicopter_x.launch" />
</launch>

2
launch/gazebo_iris_empty_world.launch

@ -1,6 +1,6 @@ @@ -1,6 +1,6 @@
<launch>
<include file="$(find mav_gazebo)/launch/iris_empty_world_with_joy.launch" />
<include file="$(find px4)/launch/multicopter.launch" />
<include file="$(find px4)/launch/multicopter_w.launch" />
</launch>

2
launch/gazebo_iris_outdoor_world.launch

@ -1,6 +1,6 @@ @@ -1,6 +1,6 @@
<launch>
<include file="$(find mav_gazebo)/launch/iris_outdoor_world_with_joy.launch" />
<include file="$(find px4)/launch/multicopter.launch" />
<include file="$(find px4)/launch/multicopter_x.launch" />
</launch>

1
launch/multicopter.launch

@ -19,6 +19,7 @@ @@ -19,6 +19,7 @@
<param name="MC_YAWRATE_P" type="double" value="0.5" />
<param name="MC_MAN_R_MAX" type="double" value="10.0" />
<param name="MC_MAN_P_MAX" type="double" value="10.0" />
<param name="mixer" type="string" value="x" />
</group>
</launch>

9
launch/multicopter_w.launch

@ -0,0 +1,9 @@ @@ -0,0 +1,9 @@
<launch>
<include file="$(find px4)/launch/multicopter.launch" />
<group ns="px4_multicopter">
<param name="mixer" type="string" value="w" />
</group>
</launch>

9
launch/multicopter_x.launch

@ -0,0 +1,9 @@ @@ -0,0 +1,9 @@
<launch>
<include file="$(find px4)/launch/multicopter.launch" />
<group ns="px4_multicopter">
<param name="mixer" type="string" value="x" />
</group>
</launch>

20
src/platforms/ros/nodes/mc_mixer/mc_mixer.cpp

@ -41,6 +41,7 @@ @@ -41,6 +41,7 @@
#include <px4.h>
#include <lib/mathlib/mathlib.h>
#include <mav_msgs/MotorSpeed.h>
#include <string>
class MultirotorMixer
{
@ -118,7 +119,7 @@ const MultirotorMixer::Rotor *_config_index[4] = { @@ -118,7 +119,7 @@ const MultirotorMixer::Rotor *_config_index[4] = {
MultirotorMixer::MultirotorMixer():
_n(),
_rotor_count(4),
_rotors(_config_index[3]) //XXX hardcoded
_rotors(_config_index[0])
{
_sub = _n.subscribe("actuator_controls_0", 1, &MultirotorMixer::actuatorControlsCallback, this);
_pub = _n.advertise<mav_msgs::MotorSpeed>("/mixed_motor_commands", 10);
@ -131,6 +132,10 @@ MultirotorMixer::MultirotorMixer(): @@ -131,6 +132,10 @@ MultirotorMixer::MultirotorMixer():
_n.setParam("motor_offset_radps", 600.0);
}
if (!_n.hasParam("mixer")) {
_n.setParam("mixer", "x");
}
_sub_actuator_armed = _n.subscribe("actuator_armed", 1, &MultirotorMixer::actuatorArmedCallback, this);
}
@ -206,6 +211,19 @@ void MultirotorMixer::actuatorControlsCallback(const PX4_TOPIC_T(actuator_contro @@ -206,6 +211,19 @@ void MultirotorMixer::actuatorControlsCallback(const PX4_TOPIC_T(actuator_contro
inputs.control[i] = msg.control[i];
}
// switch mixer if necessary
std::string mixer_name;
_n.getParamCached("mixer", mixer_name);
if (mixer_name == "x") {
_rotors = _config_index[0];
} else if (mixer_name == "+") {
_rotors = _config_index[1];
} else if (mixer_name == "e") {
_rotors = _config_index[2];
} else if (mixer_name == "w") {
_rotors = _config_index[3];
}
// mix
mix();

Loading…
Cancel
Save