mirror of
https://gitee.com/xiaohuolufeihua/bizhang_-obav.git
synced 2026-05-21 01:12:11 +00:00
ros sim: use ardrone model
This commit is contained in:
@@ -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>
|
||||
|
||||
@@ -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>
|
||||
|
||||
@@ -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;
|
||||
|
||||
@@ -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);
|
||||
|
||||
Reference in New Issue
Block a user