Skip to content

Commit

Permalink
vision: by default, do not send ODOMETRY Mavlink msgs
Browse files Browse the repository at this point in the history
  • Loading branch information
TSC21 authored and LorenzMeier committed Jun 24, 2018
1 parent 3c7d18d commit fcee53f
Show file tree
Hide file tree
Showing 2 changed files with 6 additions and 4 deletions.
3 changes: 2 additions & 1 deletion models/rotors_description/urdf/component_snippets.xacro
Original file line number Diff line number Diff line change
Expand Up @@ -135,7 +135,7 @@
</xacro:macro>

<!-- Macro to add the mavlink interface. -->
<xacro:macro name="mavlink_interface_macro" params="namespace imu_sub_topic gps_sub_topic mavlink_addr mavlink_udp_port serial_enabled serial_device baudrate qgc_addr qgc_udp_port hil_mode hil_state_level vehicle_is_tailsitter">
<xacro:macro name="mavlink_interface_macro" params="namespace imu_sub_topic gps_sub_topic mavlink_addr mavlink_udp_port serial_enabled serial_device baudrate qgc_addr qgc_udp_port hil_mode hil_state_level vehicle_is_tailsitter send_odometry">
<gazebo>
<plugin name="mavlink_interface" filename="libgazebo_mavlink_interface.so">
<robotNamespace>${namespace}</robotNamespace>
Expand All @@ -151,6 +151,7 @@
<hil_mode>$(arg hil_mode)</hil_mode>
<hil_state_level>$(arg hil_state_level)</hil_state_level>
<vehicle_is_tailsitter>$(arg vehicle_is_tailsitter)</vehicle_is_tailsitter>
<send_odometry>$(arg send_odometry)</send_odometry>
<motorSpeedCommandPubTopic>/gazebo/command/motor_speed</motorSpeedCommandPubTopic>
<control_channels>
<channel name="rotor1">
Expand Down
7 changes: 4 additions & 3 deletions models/rotors_description/urdf/iris_base.xacro
Original file line number Diff line number Diff line change
Expand Up @@ -14,6 +14,7 @@
<xacro:arg name='qgc_udp_port' default='14550' />
<xacro:arg name='hil_mode' default='false' />
<xacro:arg name='hil_state_level' default='false' />
<xacro:arg name='send_odometry' default='false' />
<xacro:arg name='vehicle_is_tailsitter' default='false' />
<xacro:arg name='visual_material' default='DarkGrey' />
<xacro:arg name='enable_mavlink_interface' default='true' />
Expand Down Expand Up @@ -42,14 +43,14 @@
/>
</xacro:if>


<!-- Instantiate gps plugin. -->
<xacro:gps_plugin_macro
namespace="${namespace}"
gps_noise="true"
>
</xacro:gps_plugin_macro>

<xacro:if value="$(arg enable_mavlink_interface)">
<!-- Instantiate mavlink telemetry interface. -->
<xacro:mavlink_interface_macro
Expand All @@ -66,6 +67,7 @@
hil_mode="$(arg hil_mode)"
hil_state_level="$(arg hil_state_level)"
vehicle_is_tailsitter="$(arg vehicle_is_tailsitter)"
send_odometry="$(arg send_odometry)"
>
</xacro:mavlink_interface_macro>
</xacro:if>
Expand Down Expand Up @@ -154,4 +156,3 @@
</xacro:if>

</robot>

0 comments on commit fcee53f

Please sign in to comment.