Skip to content
New issue

Have a question about this project? Sign up for a free GitHub account to open an issue and contact its maintainers and the community.

By clicking “Sign up for GitHub”, you agree to our terms of service and privacy statement. We’ll occasionally send you account related emails.

Already on GitHub? Sign in to your account

Updated hummingbird.xacro compatibility with multirotor_base #7

Open
wants to merge 2 commits into
base: master
Choose a base branch
from
Open
Show file tree
Hide file tree
Changes from all commits
Commits
File filter

Filter by extension

Filter by extension

Conversations
Failed to load comments.
Loading
Jump to
Jump to file
Failed to load files.
Loading
Diff view
Diff view
14 changes: 13 additions & 1 deletion rotors_description/urdf/hummingbird.xacro
Original file line number Diff line number Diff line change
Expand Up @@ -25,6 +25,8 @@ for Quadrocopter Control by Jian Wang et al.) -->
<xacro:property name="namespace" value="hummingbird" />
<xacro:property name="rotor_velocity_slowdown_sim" value="10" />
<xacro:property name="mesh_file" value="hummingbird.dae" />
<xacro:property name="mesh_scale" value="1 1 1"/>
<xacro:property name="mesh_scale_prop" value=".12 .12 .12"/>
<xacro:property name="mass" value="0.68" /> <!-- [kg] -->
<xacro:property name="body_width" value="0.1" /> <!-- [m] -->
<xacro:property name="body_height" value="0.12" /> <!-- [m] -->
Expand Down Expand Up @@ -63,7 +65,9 @@ for Quadrocopter Control by Jian Wang et al.) -->
mass="${mass}"
body_width="${body_width}"
body_height="${body_height}"
mesh_file="${mesh_file}">
mesh_file="${mesh_file}"
mesh_scale="${mesh_scale}"
color="DarkGrey">
<xacro:insert_block name="body_inertia" />
</xacro:multirotor_base_macro>

Expand All @@ -83,6 +87,8 @@ for Quadrocopter Control by Jian Wang et al.) -->
motor_number="0"
rotor_drag_coefficient="${rotor_drag_coefficient}"
rolling_moment_coefficient="${rolling_moment_coefficient}"
mesh ="propeller"
mesh_scale="${mesh_scale_prop}"
color="Red">
<origin xyz="${arm_length} 0 ${rotor_offset_top}" rpy="0 0 0" />
<xacro:insert_block name="rotor_inertia" />
Expand All @@ -103,6 +109,8 @@ for Quadrocopter Control by Jian Wang et al.) -->
motor_number="1"
rotor_drag_coefficient="${rotor_drag_coefficient}"
rolling_moment_coefficient="${rolling_moment_coefficient}"
mesh ="propeller"
mesh_scale="${mesh_scale_prop}"
color="Blue">
<origin xyz="0 ${arm_length} ${rotor_offset_top}" rpy="0 0 0" />
<xacro:insert_block name="rotor_inertia" />
Expand All @@ -123,6 +131,8 @@ for Quadrocopter Control by Jian Wang et al.) -->
motor_number="2"
rotor_drag_coefficient="${rotor_drag_coefficient}"
rolling_moment_coefficient="${rolling_moment_coefficient}"
mesh ="propeller"
mesh_scale="${mesh_scale_prop}"
color="Blue">
<origin xyz="-${arm_length} 0 ${rotor_offset_top}" rpy="0 0 0" />
<xacro:insert_block name="rotor_inertia" />
Expand All @@ -143,6 +153,8 @@ for Quadrocopter Control by Jian Wang et al.) -->
motor_number="3"
rotor_drag_coefficient="${rotor_drag_coefficient}"
rolling_moment_coefficient="${rolling_moment_coefficient}"
mesh ="propeller"
mesh_scale="${mesh_scale_prop}"
color="Blue">
<origin xyz="0 -${arm_length} ${rotor_offset_top}" rpy="0 0 0" />
<xacro:insert_block name="rotor_inertia" />
Expand Down
2 changes: 1 addition & 1 deletion rotors_gazebo_plugins/src/gazebo_odometry_plugin.cpp
Original file line number Diff line number Diff line change
Expand Up @@ -167,7 +167,7 @@ void GazeboOdometryPlugin::Load(physics::ModelPtr _model, sdf::ElementPtr _sdf)
noise_normal_angular_velocity.z * noise_normal_angular_velocity.z;
twist_covariance = twist_covd.asDiagonal();

link_name_ = namespace_ + "/" + link_name_;
//link_name_ = namespace_ + "/" + link_name_;

// Listen to the update event. This event is broadcast every
// simulation iteration.
Expand Down