Skip to content

Commit

Permalink
Add macros for crazyflie's sensors
Browse files Browse the repository at this point in the history
  • Loading branch information
gsilano committed Dec 17, 2019
1 parent a9388a7 commit 5504846
Showing 1 changed file with 55 additions and 0 deletions.
55 changes: 55 additions & 0 deletions rotors_description/urdf/component_snippets.xacro
Original file line number Diff line number Diff line change
Expand Up @@ -867,6 +867,61 @@
</xacro:imu_plugin_macro>
</xacro:macro>

<xacro:macro name="crazyflie2_odometry" params="namespace parent_link">
<xacro:odometry_plugin_macro
namespace="${namespace}"
odometry_sensor_suffix=""
parent_link="${parent_link}"
pose_topic="pose"
pose_with_covariance_topic="pose_with_covariance"
position_topic="position"
transform_topic="transform"
odometry_topic="odometry"
parent_frame_id="world"
child_frame_id="${namespace}/base_link"
mass_odometry_sensor="0.00001"
measurement_divisor="10"
measurement_delay="0"
unknown_delay="0.0"
noise_normal_position="0 0 0"
noise_normal_quaternion="0 0 0"
noise_normal_linear_velocity="0 0 0"
noise_normal_angular_velocity="0 0 0"
noise_uniform_position="0 0 0"
noise_uniform_quaternion="0 0 0"
noise_uniform_linear_velocity="0 0 0"
noise_uniform_angular_velocity="0 0 0"
enable_odometry_map="false"
odometry_map=""
image_scale="">
<inertia ixx="0.00001" ixy="0.0" ixz="0.0" iyy="0.00001" iyz="0.0" izz="0.00001" /> <!-- [kg m^2] [kg m^2] [kg m^2] [kg m^2] [kg m^2] [kg m^2] -->
<origin xyz="0.0 0.0 0.0" rpy="0.0 0.0 0.0" />
</xacro:odometry_plugin_macro>
</xacro:macro>

<xacro:macro name="crazyflie2_imu" params="namespace parent_link">
<!-- Mount an MPU-9250 IMU. -->
<xacro:imu_plugin_macro
namespace="${namespace}"
imu_suffix=""
parent_link="${parent_link}"
imu_topic="imu"
measurement_delay="0"
measurement_divisor="1"
mass_imu_sensor="0.00001"
gyroscope_noise_density="0.000175"
gyroscope_random_walk="0.0105"
gyroscope_bias_correlation_time="1000.0"
gyroscope_turn_on_bias_sigma= "0.09"
accelerometer_noise_density="0.003"
accelerometer_random_walk="0.18"
accelerometer_bias_correlation_time="300.0"
accelerometer_turn_on_bias_sigma="0.588">
<inertia ixx="0.00001" ixy="0.0" ixz="0.0" iyy="0.00001" iyz="0.0" izz="0.00001" />
<origin xyz="0 0 0" rpy="0 0 0" />
</xacro:imu_plugin_macro>
</xacro:macro>

<xacro:macro name="default_gps" params="namespace parent_link">
<!-- Default GPS. -->
<xacro:gps_plugin_macro
Expand Down

0 comments on commit 5504846

Please sign in to comment.