Browse Source

update ros launch files and nodes for update of rotors_simulator

sbg
Thomas Gubler 10 years ago
parent
commit
c07c39bc43
  1. 7
      launch/ardrone.launch
  2. 9
      launch/gazebo_ardrone_empty_world.launch
  3. 11
      launch/gazebo_ardrone_empty_world_offboard_attitudedemo.launch
  4. 11
      launch/gazebo_ardrone_empty_world_offboard_positiondemo.launch
  5. 9
      launch/gazebo_ardrone_house_world.launch
  6. 9
      launch/gazebo_iris_empty_world.launch
  7. 7
      launch/gazebo_iris_house_world.launch
  8. 7
      launch/gazebo_iris_outdoor_world.launch
  9. 7
      launch/iris.launch
  10. 3
      launch/multicopter.launch
  11. 7
      launch/multicopter_w.launch
  12. 7
      launch/multicopter_x.launch
  13. 6
      src/platforms/ros/nodes/mc_mixer/mc_mixer.cpp

7
launch/ardrone.launch

@ -1,8 +1,11 @@ @@ -1,8 +1,11 @@
<launch>
<arg name="ns"/>
<include file="$(find px4)/launch/multicopter_x.launch" />
<include file="$(find px4)/launch/multicopter_x.launch">
<arg name="ns" value="$(arg ns)"/>
</include>
<group ns="px4_multicopter">
<group ns="$(arg ns)">
<param name="MPC_XY_P" type="double" value="1.0" />
<param name="MPC_XY_FF" type="double" value="0.0" />
<param name="MPC_XY_VEL_P" type="double" value="0.01" />

9
launch/gazebo_ardrone_empty_world.launch

@ -4,15 +4,18 @@ @@ -4,15 +4,18 @@
<arg name="gui" default="true"/>
<arg name="enable_logging" default="false"/>
<arg name="enable_ground_truth" default="false"/>
<arg name="log_file" default="ardrone"/>
<arg name="ns" default="ardrone"/>
<arg name="log_file" default="$(arg ns)"/>
<include file="$(find rotors_gazebo)/launch/ardrone_empty_world_with_joy.launch">
<include file="$(find rotors_gazebo)/launch/ardrone_empty_world.launch">
<arg name="headless" value="$(arg headless)"/>
<arg name="gui" value="$(arg gui)"/>
<arg name="enable_logging" value="$(arg enable_logging)" />
<arg name="enable_ground_truth" value="$(arg enable_ground_truth)" />
<arg name="log_file" value="$(arg log_file)"/>
</include>
<include file="$(find px4)/launch/ardrone.launch" />
<include file="$(find px4)/launch/ardrone.launch">
<arg name="ns" value="$(arg ns)"/>
</include>
</launch>

11
launch/gazebo_ardrone_empty_world_offboard_attitudedemo.launch

@ -1,9 +1,12 @@ @@ -1,9 +1,12 @@
<launch>
<arg name="ns" default="ardrone"/>
<include file="$(find px4)/launch/gazebo_ardrone_empty_world.launch" />
<include file="$(find px4)/launch/gazebo_ardrone_empty_world.launch">
<arg name="ns" value="$(arg ns)"/>
</include>
<include file="$(find px4)/launch/mavros_sitl.launch" />
<node pkg="px4" name="demo_offboard_attitude_setpoints" type="demo_offboard_attitude_setpoints"/>
<group ns="$(arg ns)">
<node pkg="px4" name="demo_offboard_attitude_setpoints" type="demo_offboard_attitude_setpoints"/>
</group>
</launch>

11
launch/gazebo_ardrone_empty_world_offboard_positiondemo.launch

@ -1,9 +1,12 @@ @@ -1,9 +1,12 @@
<launch>
<arg name="ns" default="ardrone"/>
<include file="$(find px4)/launch/gazebo_ardrone_empty_world.launch" />
<include file="$(find px4)/launch/gazebo_ardrone_empty_world.launch">
<arg name="ns" value="$(arg ns)"/>
</include>
<include file="$(find px4)/launch/mavros_sitl.launch" />
<node pkg="px4" name="demo_offboard_position_setpoints" type="demo_offboard_position_setpoints"/>
<group ns="$(arg ns)">
<node pkg="px4" name="demo_offboard_position_setpoints" type="demo_offboard_position_setpoints"/>
</group>
</launch>

9
launch/gazebo_ardrone_house_world.launch

@ -4,15 +4,18 @@ @@ -4,15 +4,18 @@
<arg name="gui" default="true"/>
<arg name="enable_logging" default="false"/>
<arg name="enable_ground_truth" default="true"/>
<arg name="log_file" default="ardrone"/>
<arg name="ns" default="ardrone"/>
<arg name="log_file" default="$(arg ns)"/>
<include file="$(find rotors_gazebo)/launch/ardrone_house_world_with_joy.launch">
<include file="$(find rotors_gazebo)/launch/ardrone_house_world.launch">
<arg name="headless" value="$(arg headless)"/>
<arg name="gui" value="$(arg gui)"/>
<arg name="enable_logging" value="$(arg enable_logging)" />
<arg name="enable_ground_truth" value="$(arg enable_ground_truth)" />
<arg name="log_file" value="$(arg log_file)"/>
</include>
<include file="$(find px4)/launch/ardrone.launch" />
<include file="$(find px4)/launch/ardrone.launch">
<arg name="ns" value="$(arg ns)"/>
</include>
</launch>

9
launch/gazebo_iris_empty_world.launch

@ -4,15 +4,18 @@ @@ -4,15 +4,18 @@
<arg name="gui" default="true"/>
<arg name="enable_logging" default="false"/>
<arg name="enable_ground_truth" default="true"/>
<arg name="log_file" default="iris"/>
<arg name="ns" default="iris"/>
<arg name="log_file" default="$(arg ns)"/>
<include file="$(find rotors_gazebo)/launch/iris_empty_world_with_joy.launch">
<include file="$(find rotors_gazebo)/launch/iris_empty_world.launch">
<arg name="headless" value="$(arg headless)"/>
<arg name="gui" value="$(arg gui)"/>
<arg name="enable_logging" value="$(arg enable_logging)" />
<arg name="enable_ground_truth" value="$(arg enable_ground_truth)" />
<arg name="log_file" value="$(arg log_file)"/>
</include>
<include file="$(find px4)/launch/iris.launch" />
<include file="$(find px4)/launch/iris.launch">
<arg name="ns" value="$(arg ns)"/>
</include>
</launch>

7
launch/gazebo_iris_house_world.launch

@ -4,7 +4,8 @@ @@ -4,7 +4,8 @@
<arg name="gui" default="true"/>
<arg name="enable_logging" default="false"/>
<arg name="enable_ground_truth" default="true"/>
<arg name="log_file" default="iris"/>
<arg name="ns" default="iris"/>
<arg name="log_file" default="$(arg ns)"/>
<include file="$(find rotors_gazebo)/launch/iris_house_world_with_joy.launch">
<arg name="headless" value="$(arg headless)"/>
@ -13,6 +14,8 @@ @@ -13,6 +14,8 @@
<arg name="enable_ground_truth" value="$(arg enable_ground_truth)" />
<arg name="log_file" value="$(arg log_file)"/>
</include>
<include file="$(find px4)/launch/iris.launch" />
<include file="$(find px4)/launch/iris.launch">
<arg name="ns" value="$(arg ns)"/>
</include>
</launch>

7
launch/gazebo_iris_outdoor_world.launch

@ -4,7 +4,8 @@ @@ -4,7 +4,8 @@
<arg name="gui" default="true"/>
<arg name="enable_logging" default="false"/>
<arg name="enable_ground_truth" default="true"/>
<arg name="log_file" default="iris"/>
<arg name="ns" default="iris"/>
<arg name="log_file" default="$(arg ns)"/>
<include file="$(find rotors_gazebo)/launch/iris_outdoor_world_with_joy.launch">
<arg name="headless" value="$(arg headless)"/>
@ -13,6 +14,8 @@ @@ -13,6 +14,8 @@
<arg name="enable_ground_truth" value="$(arg enable_ground_truth)" />
<arg name="log_file" value="$(arg log_file)"/>
</include>
<include file="$(find px4)/launch/iris.launch" />
<include file="$(find px4)/launch/iris.launch">
<arg name="ns" value="$(arg ns)"/>
</include>
</launch>

7
launch/iris.launch

@ -1,8 +1,11 @@ @@ -1,8 +1,11 @@
<launch>
<arg name="ns"/>
<include file="$(find px4)/launch/multicopter_w.launch" />
<include file="$(find px4)/launch/multicopter_w.launch">
<arg name="ns" value="$(arg ns)"/>
</include>
<group ns="px4_multicopter">
<group ns="$(arg ns)">
<param name="mixer" type="string" value="i" />
<param name="MPC_XY_P" type="double" value="1.0" />
<param name="MPC_XY_FF" type="double" value="0.0" />

3
launch/multicopter.launch

@ -1,6 +1,7 @@ @@ -1,6 +1,7 @@
<launch>
<arg name="ns"/>
<group ns="px4_multicopter">
<group ns="$(arg ns)">
<node pkg="joy" name="joy_node" type="joy_node"/>
<node pkg="px4" name="manual_input" type="manual_input"/>
<node pkg="px4" name="commander" type="commander"/>

7
launch/multicopter_w.launch

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

7
launch/multicopter_x.launch

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

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

@ -40,7 +40,7 @@ @@ -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(): @@ -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 @@ -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);

Loading…
Cancel
Save