aboutsummaryrefslogtreecommitdiff
diff options
context:
space:
mode:
-rw-r--r--launch/ardrone.launch1
-rw-r--r--launch/gazebo_ardrone_empty_world.launch1
-rw-r--r--src/platforms/ros/nodes/attitude_estimator/attitude_estimator.cpp4
3 files changed, 5 insertions, 1 deletions
diff --git a/launch/ardrone.launch b/launch/ardrone.launch
index d53333b11..3173e7cf1 100644
--- a/launch/ardrone.launch
+++ b/launch/ardrone.launch
@@ -9,6 +9,7 @@
<param name="MPC_XY_VEL_I" type="double" value="0.0" />
<param name="MPC_XY_VEL_D" type="double" value="0.01" />
<param name="MPC_XY_VEL_MAX" type="double" value="2.0" />
+ <param name="vehicle_model" type="string" value="ardrone" />
</group>
</launch>
diff --git a/launch/gazebo_ardrone_empty_world.launch b/launch/gazebo_ardrone_empty_world.launch
index 395e70b00..063d51096 100644
--- a/launch/gazebo_ardrone_empty_world.launch
+++ b/launch/gazebo_ardrone_empty_world.launch
@@ -1,6 +1,7 @@
<launch>
<include file="$(find mav_gazebo)/launch/ardrone_empty_world_with_joy.launch" />
+<!-- <include file="$(find mav_gazebo)/launch/ardrone_empty_world.launch" /> -->
<include file="$(find px4)/launch/ardrone.launch" />
</launch>
diff --git a/src/platforms/ros/nodes/attitude_estimator/attitude_estimator.cpp b/src/platforms/ros/nodes/attitude_estimator/attitude_estimator.cpp
index 1d36e3d99..a3e4bca30 100644
--- a/src/platforms/ros/nodes/attitude_estimator/attitude_estimator.cpp
+++ b/src/platforms/ros/nodes/attitude_estimator/attitude_estimator.cpp
@@ -48,9 +48,11 @@
AttitudeEstimator::AttitudeEstimator() :
_n(),
// _sub_modelstates(_n.subscribe("/gazebo/model_states", 1, &AttitudeEstimator::ModelStatesCallback, this)),
- _sub_imu(_n.subscribe("/px4_multicopter/imu", 1, &AttitudeEstimator::ImuCallback, this)),
_vehicle_attitude_pub(_n.advertise<px4::vehicle_attitude>("vehicle_attitude", 1))
{
+ std::string vehicle_model;
+ _n.param("vehicle_model", vehicle_model, std::string("iris"));
+ _sub_imu = _n.subscribe("/" + vehicle_model + "/imu", 1, &AttitudeEstimator::ImuCallback, this);
}
void AttitudeEstimator::ModelStatesCallback(const gazebo_msgs::ModelStatesConstPtr &msg)