aboutsummaryrefslogtreecommitdiff
diff options
context:
space:
mode:
-rw-r--r--launch/gazebo_multicopter.launch2
-rw-r--r--launch/multicopter.launch6
-rw-r--r--src/platforms/ros/nodes/attitude_estimator/attitude_estimator.cpp6
-rw-r--r--src/platforms/ros/nodes/mc_mixer/mc_mixer.cpp2
4 files changed, 8 insertions, 8 deletions
diff --git a/launch/gazebo_multicopter.launch b/launch/gazebo_multicopter.launch
index febf7bdc0..8091e3ff2 100644
--- a/launch/gazebo_multicopter.launch
+++ b/launch/gazebo_multicopter.launch
@@ -1,6 +1,6 @@
<launch>
-<include file="$(find mav_gazebo)/launch/vtol_empty_world_with_joy.launch" />
+<include file="$(find mav_gazebo)/launch/ardrone_empty_world_with_joy.launch" />
<include file="$(find px4)/launch/multicopter.launch" />
</launch>
diff --git a/launch/multicopter.launch b/launch/multicopter.launch
index 9956c871d..0a4b8c26d 100644
--- a/launch/multicopter.launch
+++ b/launch/multicopter.launch
@@ -14,9 +14,9 @@
<param name="MC_ROLLRATE_D" type="double" value="0.0" />
<param name="MC_PITCHRATE_P" type="double" value="0.05" />
<param name="MC_PITCHRATE_D" type="double" value="0.0" />
- <param name="MC_YAW_FF" type="double" value="0.0" />
- <param name="MC_YAW_P" type="double" value="1.0" />
- <param name="MC_YAWRATE_P" type="double" value="0.2" />
+ <param name="MC_YAW_FF" type="double" value="0" />
+ <param name="MC_YAW_P" type="double" value="5.0" />
+ <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" />
</group>
diff --git a/src/platforms/ros/nodes/attitude_estimator/attitude_estimator.cpp b/src/platforms/ros/nodes/attitude_estimator/attitude_estimator.cpp
index ce863d10e..920334363 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<px4::vehicle_attitude>("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 e2180af41..3867d448e 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<mav_msgs::MotorSpeed>("/mixed_motor_commands", 10);