update ros launch files and nodes for update of rotors_simulator

This commit is contained in:
Thomas Gubler 2015-02-28 18:15:51 +01:00
parent 1837440e43
commit c07c39bc43
13 changed files with 67 additions and 33 deletions

View File

@ -1,8 +1,11 @@
<launch> <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_P" type="double" value="1.0" />
<param name="MPC_XY_FF" type="double" value="0.0" /> <param name="MPC_XY_FF" type="double" value="0.0" />
<param name="MPC_XY_VEL_P" type="double" value="0.01" /> <param name="MPC_XY_VEL_P" type="double" value="0.01" />

View File

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

View File

@ -1,9 +1,12 @@
<launch> <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" /> <include file="$(find px4)/launch/mavros_sitl.launch" />
<group ns="$(arg ns)">
<node pkg="px4" name="demo_offboard_attitude_setpoints" type="demo_offboard_attitude_setpoints"/> <node pkg="px4" name="demo_offboard_attitude_setpoints" type="demo_offboard_attitude_setpoints"/>
</group>
</launch> </launch>

View File

@ -1,9 +1,12 @@
<launch> <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" /> <include file="$(find px4)/launch/mavros_sitl.launch" />
<group ns="$(arg ns)">
<node pkg="px4" name="demo_offboard_position_setpoints" type="demo_offboard_position_setpoints"/> <node pkg="px4" name="demo_offboard_position_setpoints" type="demo_offboard_position_setpoints"/>
</group>
</launch> </launch>

View File

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

View File

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

View File

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

View File

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

View File

@ -1,8 +1,11 @@
<launch> <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="mixer" type="string" value="i" />
<param name="MPC_XY_P" type="double" value="1.0" /> <param name="MPC_XY_P" type="double" value="1.0" />
<param name="MPC_XY_FF" type="double" value="0.0" /> <param name="MPC_XY_FF" type="double" value="0.0" />

View File

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

View File

@ -1,8 +1,11 @@
<launch> <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" /> <param name="mixer" type="string" value="w" />
</group> </group>

View File

@ -1,8 +1,11 @@
<launch> <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" /> <param name="mixer" type="string" value="x" />
</group> </group>

View File

@ -40,7 +40,7 @@
#include <ros/ros.h> #include <ros/ros.h>
#include <px4.h> #include <px4.h>
#include <lib/mathlib/mathlib.h> #include <lib/mathlib/mathlib.h>
#include <mav_msgs/MotorSpeed.h> #include <mav_msgs/CommandMotorSpeed.h>
#include <string> #include <string>
class MultirotorMixer class MultirotorMixer
@ -129,7 +129,7 @@ MultirotorMixer::MultirotorMixer():
_rotors(_config_index[0]) _rotors(_config_index[0])
{ {
_sub = _n.subscribe("actuator_controls_0", 1, &MultirotorMixer::actuatorControlsCallback, this); _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")) { if (!_n.hasParam("motor_scaling_radps")) {
_n.setParam("motor_scaling_radps", 150.0); _n.setParam("motor_scaling_radps", 150.0);
@ -237,7 +237,7 @@ void MultirotorMixer::actuatorControlsCallback(const px4::actuator_controls_0 &m
mix(); mix();
// publish message // publish message
mav_msgs::MotorSpeed rotor_vel_msg; mav_msgs::CommandMotorSpeed rotor_vel_msg;
double scaling; double scaling;
double offset; double offset;
_n.getParamCached("motor_scaling_radps", scaling); _n.getParamCached("motor_scaling_radps", scaling);