This commit is contained in:
parent
23532118c4
commit
76027ffc09
|
@ -1,13 +1,26 @@
|
|||
<launch>
|
||||
<arg name="path_save" default="/home/pi/bags"/>
|
||||
<arg name="file_name" default="test.bag"/>
|
||||
<!-- RUN mavros -->
|
||||
<arg name="fcu_url" default="/dev/ttyAMA0:115200" />
|
||||
<arg name="gcs_url" default="" />
|
||||
<arg name="tgt_system" default="1" />
|
||||
<arg name="tgt_component" default="1" />
|
||||
<arg name="log_output" default="screen" />
|
||||
|
||||
<group ns="record">
|
||||
<param name="path_save" type="str" value="$(arg path_save)" />
|
||||
<param name="file_name" type="str" value="$(arg file_name)" />
|
||||
<node name="record_ros" pkg="record_ros" type="record_ros" output="screen" respawn="true"/>
|
||||
</group>
|
||||
<include file="$(find mavros)/launch/node.launch">
|
||||
<arg name="pluginlists_yaml" value="$(find mavros)/launch/apm_pluginlists.yaml" />
|
||||
<arg name="config_yaml" value="$(find mavros)/launch/apm_config.yaml" />
|
||||
|
||||
<arg name="fcu_url" value="$(arg fcu_url)" />
|
||||
<arg name="gcs_url" value="$(arg gcs_url)" />
|
||||
<arg name="tgt_system" value="$(arg tgt_system)" />
|
||||
<arg name="tgt_component" value="$(arg tgt_component)" />
|
||||
<arg name="log_output" value="$(arg log_output)" />
|
||||
</include>
|
||||
|
||||
<!-- set streaming rate -->
|
||||
<node pkg="rosservice" type="rosservice" name="freq" args="call /mavros/set_stream_rate 0 10 1" output="screen" />
|
||||
|
||||
<!-- run xbee -->
|
||||
<node pkg="xbee_ros_node" type="xbee_mav" name="xbee_mav" args="slave swarm" output="screen" />
|
||||
<param name="Xbee_In_From_Buzz" type="str" value="outMavlink" />
|
||||
<param name="Xbee_Out_To_Buzz" type="str" value="inMavlink" />
|
||||
|
@ -15,18 +28,17 @@
|
|||
<param name="No_of_dev" type="int" value="3" />
|
||||
<param name="Xbee_Out_To_Controller" type="str" value="mav_dji_cmd" />
|
||||
|
||||
|
||||
<!-- run rosbuzz -->
|
||||
<node name="rosbuzz_node" pkg="rosbuzz" type="rosbuzz_node" respawn="false" output="screen" >
|
||||
<rosparam file="/home/pi/ros_catkin_ws/src/ROSBuzz/launch/launch_config/solo.yaml"/>
|
||||
<param name="bzzfile_name" value="/home/pi/ros_catkin_ws/src/ROSBuzz/src/testalone.bzz" />
|
||||
<param name="rcclient" value="true" />
|
||||
<param name="rcclient" value="true" />
|
||||
<param name="rcservice_name" value="/buzzcmd" />
|
||||
<param name="in_payload" value="/inMavlink"/>
|
||||
<param name="out_payload" value="/outMavlink"/>
|
||||
<param name="robot_id" value="3"/>
|
||||
<param name="No_of_Robots" value="3"/>
|
||||
<param name="stand_by" value="$(env ROS_WS)/src/ROSBuzz/src/stand_by.bo"/>
|
||||
<param name="stand_by" value="/home/pi/ros_catkin_ws/src/ROSBuzz/src/stand_by.bo"/>
|
||||
</node>
|
||||
|
||||
</launch>
|
||||
|
||||
|
|
|
@ -0,0 +1,20 @@
|
|||
#! /bin/bash
|
||||
function takeoff {
|
||||
rosservice call /buzzcmd 0 22 0 0 0 0 0 0 0 0
|
||||
}
|
||||
function land {
|
||||
rosservice call /buzzcmd 0 21 0 0 0 0 0 0 0 0
|
||||
}
|
||||
function record {
|
||||
rosbag record /flight_status /global_position /dji_sdk/local_position /neighbours_pos /power_status /guidance/obstacle_distance /guidance/front_depth_image/compressedDepth /guidance/right_depth_image/compressedDepth /guidance/left_depth_image/compressedDepth /guidance/bottom_depth_image/compressedDepth /guidance/back_depth_image/compressedDepth
|
||||
}
|
||||
function clean {
|
||||
sudo rm /var/log/upstart/robot*
|
||||
sudo rm /var/log/upstart/x3s*
|
||||
}
|
||||
function startrobot {
|
||||
sudo service robot start
|
||||
}
|
||||
function stoprobot {
|
||||
sudo service robot stop
|
||||
}
|
Loading…
Reference in New Issue