diff --git a/CMakeLists.txt b/CMakeLists.txt index 9cb3fac..28df175 100644 --- a/CMakeLists.txt +++ b/CMakeLists.txt @@ -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 diff --git a/launch/husky.launch b/launch/husky.launch new file mode 100644 index 0000000..bb883c5 --- /dev/null +++ b/launch/husky.launch @@ -0,0 +1,59 @@ + + + + + + + + + + + + + + + + magnetic_declination_radians: 0 + roll_offset: 0 + pitch_offset: 0 + yaw_offset: 0 + zero_altitude: false + broadcast_utm_transform: false + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + diff --git a/launch/launch_config/husky.yaml b/launch/launch_config/husky.yaml new file mode 100644 index 0000000..c878cc4 --- /dev/null +++ b/launch/launch_config/husky.yaml @@ -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 diff --git a/src/roscontroller.cpp b/src/roscontroller.cpp index d21fe9c..4d4eb68 100644 --- a/src/roscontroller.cpp +++ b/src/roscontroller.cpp @@ -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*/