drone-rigide/workspace/src/detect_targets/launch/bebop-triangle-control.launch

78 lines
3.3 KiB
Text
Raw Normal View History

2019-03-11 14:24:29 +00:00
<launch>
<include file="$(find bebop_driver)/launch/bebop_node.launch" />
<node name="targets" pkg="detect_targets" type="target_publisher.py">
</node>
2019-05-24 11:13:28 +00:00
<node name="triangle" pkg="detect_targets" type="triangle_control.py" output="screen">
2019-03-11 14:24:29 +00:00
<remap from="component_centers" to="targets"/>
</node>
2019-05-24 11:13:28 +00:00
<group ns="controller_linear_x">
<include file="$(find detect_targets)/launch/control.launch" ns="external_loop">
<arg name="output" value="/controller_linear_x/internal_loop/input" />
<arg name="reset" value="/reset" />
<arg name="measure" value="/linear_x" />
</include>
<include file="$(find detect_targets)/launch/control.launch" ns="internal_loop">
<arg name="reset" value="/reset" />
</include>
</group>
<group ns="controller_linear_y">
<include file="$(find detect_targets)/launch/control.launch" ns="external_loop">
<arg name="output" value="/controller_linear_y/internal_loop/input" />
<arg name="reset" value="/reset" />
<arg name="measure" value="/linear_y" />
</include>
<include file="$(find detect_targets)/launch/control.launch" ns="internal_loop">
<arg name="reset" value="/reset" />
</include>
</group>
<include file="$(find detect_targets)/launch/control.launch" ns="controller_linear_z">
<arg name="reset" value="/reset" />
<arg name="measure" value="/linear_z" />
</include>
<include file="$(find detect_targets)/launch/control.launch" ns="controller_angular_z">
<arg name="reset" value="/reset" />
<arg name="measure" value="/angular_z" />
</include>
<node name="Dx" pkg="detect_targets" type="control_compute.py" args="derivative" output="screen">
<remap from="input" to="linear_x" />
<remap from="output" to="controller_linear_x/internal_loop/measure" />
</node>
<node name="Dy" pkg="detect_targets" type="control_compute.py" args="derivative" output="screen">
<remap from="input" to="linear_y" />
<remap from="output" to="controller_linear_y/internal_loop/measure" />
</node>
<node name="twister" pkg="detect_targets" type="twist_controls.py">
<remap from="control_linear_z" to="controller_linear_z/output" />
<remap from="control_angular_z" to="controller_angular_z/output" />
<remap from="control_linear_x" to="controller_linear_x/internal_loop/output" />
<remap from="control_linear_y" to="controller_linear_y/internal_loop/output" />
</node>
2019-03-11 14:24:29 +00:00
<node name="safe" pkg="demo_teleop" type="safe_drone_teleop.py" output="screen" launch-prefix="xterm -e">
<remap from="takeoff" to="/bebop/takeoff"/>
<remap from="land" to="/bebop/land"/>
2019-05-24 11:13:28 +00:00
<!-- <remap from="reset" to="/bebop/reset"/> -->
2019-03-11 14:24:29 +00:00
<remap from="cmd_vel_out" to="/bebop/cmd_vel"/>
<remap from="cmd_vel_in" to="/cmd_vel"/>
</node>
2019-05-24 11:13:28 +00:00
<node name="relay" pkg="topic_tools" type="relay" args="/reset">
<remap from="intopic_relay" to="/bebop/reset" />
</node>
2019-03-11 14:24:29 +00:00
<node name="view" pkg="rqt_image_view" type="rqt_image_view" args="/bebop/image_raw"/>
2019-05-24 11:13:28 +00:00
<node name="graph" pkg="rqt_graph" type="rqt_graph" output="screen"></node>
2019-03-11 14:24:29 +00:00
<node name="reconf" pkg="rqt_reconfigure" type="rqt_reconfigure"/>
<node name="pid_param" pkg="dynamic_reconfigure" type="dynparam" args="load /controller $(find drone_demo)/params/triangle-control-pid.yaml"/>
</launch>