From 6580d66d45cfb4b251e3b0f32b61161ee0d14ecb Mon Sep 17 00:00:00 2001 From: Thomas Gubler Date: Sat, 10 Jan 2015 19:14:23 +0100 Subject: [PATCH] ros sim: use ardrone model --- launch/gazebo_multicopter.launch | 2 +- launch/multicopter.launch | 6 +++--- .../ros/nodes/attitude_estimator/attitude_estimator.cpp | 6 +++--- src/platforms/ros/nodes/mc_mixer/mc_mixer.cpp | 2 +- 4 files changed, 8 insertions(+), 8 deletions(-) diff --git a/launch/gazebo_multicopter.launch b/launch/gazebo_multicopter.launch index febf7bdc07..8091e3ff2b 100644 --- a/launch/gazebo_multicopter.launch +++ b/launch/gazebo_multicopter.launch @@ -1,6 +1,6 @@ - + diff --git a/launch/multicopter.launch b/launch/multicopter.launch index 9956c871d9..0a4b8c26df 100644 --- a/launch/multicopter.launch +++ b/launch/multicopter.launch @@ -14,9 +14,9 @@ - - - + + + diff --git a/src/platforms/ros/nodes/attitude_estimator/attitude_estimator.cpp b/src/platforms/ros/nodes/attitude_estimator/attitude_estimator.cpp index ce863d10e3..9203343633 100644 --- a/src/platforms/ros/nodes/attitude_estimator/attitude_estimator.cpp +++ b/src/platforms/ros/nodes/attitude_estimator/attitude_estimator.cpp @@ -47,7 +47,7 @@ AttitudeEstimator::AttitudeEstimator() : _n(), // _sub_modelstates(_n.subscribe("/gazebo/model_states", 1, &AttitudeEstimator::ModelStatesCallback, this)), - _sub_imu(_n.subscribe("/vtol/imu", 1, &AttitudeEstimator::ImuCallback, this)), + _sub_imu(_n.subscribe("/ardrone/imu", 1, &AttitudeEstimator::ImuCallback, this)), _vehicle_attitude_pub(_n.advertise("vehicle_attitude", 1)) { } @@ -60,7 +60,7 @@ void AttitudeEstimator::ModelStatesCallback(const gazebo_msgs::ModelStatesConstP /* Convert quaternion to rotation matrix */ math::Quaternion quat; - //XXX: search for vtol or other (other than 'plane') vehicle here + //XXX: search for ardrone or other (other than 'plane') vehicle here int index = 1; quat(0) = (float)msg->pose[index].orientation.w; quat(1) = (float)msg->pose[index].orientation.x; @@ -103,7 +103,7 @@ void AttitudeEstimator::ImuCallback(const sensor_msgs::ImuConstPtr &msg) /* Convert quaternion to rotation matrix */ math::Quaternion quat; - //XXX: search for vtol or other (other than 'plane') vehicle here + //XXX: search for ardrone or other (other than 'plane') vehicle here int index = 1; quat(0) = (float)msg->orientation.w; quat(1) = (float)msg->orientation.x; diff --git a/src/platforms/ros/nodes/mc_mixer/mc_mixer.cpp b/src/platforms/ros/nodes/mc_mixer/mc_mixer.cpp index e2180af41b..3867d448e6 100644 --- a/src/platforms/ros/nodes/mc_mixer/mc_mixer.cpp +++ b/src/platforms/ros/nodes/mc_mixer/mc_mixer.cpp @@ -111,7 +111,7 @@ const MultirotorMixer::Rotor *_config_index[3] = { MultirotorMixer::MultirotorMixer(): _n(), _rotor_count(4), - _rotors(_config_index[2]) //XXX + eurocconfig hardcoded + _rotors(_config_index[0]) //XXX hardcoded { _sub = _n.subscribe("actuator_controls_0", 1, &MultirotorMixer::actuatorControlsCallback, this); _pub = _n.advertise("/mixed_motor_commands", 10);