remove prints
This commit is contained in:
parent
b5a08f2512
commit
118b3ddde5
|
@ -46,6 +46,8 @@ include_directories(
|
|||
include ${rosbuzz_INCLUDE_DIRS}
|
||||
${catkin_INCLUDE_DIRS}
|
||||
)
|
||||
# set the path to the library folder
|
||||
link_directories(/usr/local/lib)
|
||||
|
||||
# Executables
|
||||
add_executable(rosbuzz_node src/rosbuzz.cpp
|
||||
|
|
|
@ -0,0 +1,59 @@
|
|||
<launch>
|
||||
<group ns="gps">
|
||||
<!-- NavSat Serial -->
|
||||
<node pkg="nmea_comms" type="serial_node" name="nmea_serial_node" output="screen">
|
||||
<param name="port" value="$(optenv HUSKY_NAVSAT_PORT /dev/clearpath/gps)" />
|
||||
<param name="baud" value="$(optenv HUSKY_NAVSAT_BAUD 19200)" />
|
||||
</node>
|
||||
|
||||
<!-- NavSat Processing -->
|
||||
<node pkg="nmea_navsat_driver" type="nmea_topic_driver" name="nmea_topic_driver">
|
||||
</node>
|
||||
</group>
|
||||
|
||||
<node pkg="robot_localization" type="navsat_transform_node" name="navsat_transform" >
|
||||
<rosparam>
|
||||
magnetic_declination_radians: 0
|
||||
roll_offset: 0
|
||||
pitch_offset: 0
|
||||
yaw_offset: 0
|
||||
zero_altitude: false
|
||||
broadcast_utm_transform: false
|
||||
</rosparam>
|
||||
</node>
|
||||
|
||||
<!-- 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" />
|
||||
<param name="Xbee_In_From_Controller" type="str" value="xbee_cmd" / -->
|
||||
|
||||
<!-- xmee_mav Drone type and Commununication Mode -->
|
||||
<!-- node pkg="xbee_ros_node" type="xbee_mav" name="xbee_mav" args="master solo" output="screen" -->
|
||||
<node pkg="xbee_ros_node" type="xbee_mav" name="xbee_mav" args="slave swarm" output="screen" />
|
||||
<!-- node pkg="xbee_ros_node" type="xbee_mav" name="xbee_mav" args="slave solo" output="screen" -->
|
||||
<!--node pkg="xbee_ros_node" type="xbee_mav" name="xbee_mav" args="slave swarm" output="screen" -->
|
||||
<!-- xmee_mav Topics and Services Names -->
|
||||
<param name="Xbee_In_From_Buzz" type="str" value="outMavlink" />
|
||||
<param name="Xbee_Out_To_Buzz" type="str" value="inMavlink" />
|
||||
<param name="Xbee_In_From_Controller" type="str" value="xbee_cmd" />
|
||||
<param name="Xbee_Out_To_Controller" type="str" value="mav_dji_cmd" />
|
||||
|
||||
|
||||
<node pkg="dji_sdk_mistlab" type="dji_sdk_mav" name="dji_sdk_mav" output="screen"/>
|
||||
|
||||
<!-- run rosbuzz -->
|
||||
<node name="rosbuzz_node" pkg="rosbuzz" type="rosbuzz_node" respawn="false" output="screen" >
|
||||
<rosparam file="$(find rosbuzz)/launch/launch_config/husky.yaml"/>
|
||||
<param name="bzzfile_name" value="$(find rosbuzz)/script/testflockfev.bzz" />
|
||||
<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="xbee_status_srv" value="xbee_status"/>
|
||||
<param name="xbee_plugged" value="true"/>
|
||||
<param name="name" value="husky1"/>
|
||||
<param name="stand_by" value="$(find rosbuzz)/script/stand_by.bzz"/>
|
||||
</node>
|
||||
|
||||
</launch>
|
|
@ -0,0 +1,17 @@
|
|||
topics:
|
||||
gps : global_position
|
||||
localpos : local_position
|
||||
battery : power_status
|
||||
status : flight_status
|
||||
fcclient : dji_mavcmd
|
||||
setpoint : setpoint_position/local
|
||||
armclient: dji_mavarm
|
||||
modeclient: dji_mavmode
|
||||
altitude: rel_alt
|
||||
stream: set_stream_rate
|
||||
|
||||
type:
|
||||
gps : sensor_msgs/NavSatFix
|
||||
battery : mavros_msgs/BatteryStatus
|
||||
status : mavros_msgs/ExtendedState
|
||||
altitude: std_msgs/Float64
|
|
@ -128,7 +128,7 @@ namespace rosbzz_node{
|
|||
/*Set no of robots for updates TODO only when not updating*/
|
||||
//if(multi_msg)
|
||||
updates_set_robots(no_of_robots);
|
||||
ROS_INFO("ROBOTS: %i , acutal : %i",(int)no_of_robots,(int)buzzdict_size(buzz_utility::get_vm()->swarmmembers)+1);
|
||||
//ROS_INFO("ROBOTS: %i , acutal : %i",(int)no_of_robots,(int)buzzdict_size(buzz_utility::get_vm()->swarmmembers)+1);
|
||||
/*run once*/
|
||||
ros::spinOnce();
|
||||
/*loop rate of ros*/
|
||||
|
|
Loading…
Reference in New Issue