diff --git a/CMakeLists.txt b/CMakeLists.txt index a0adbeb..1e8ead7 100644 --- a/CMakeLists.txt +++ b/CMakeLists.txt @@ -9,7 +9,7 @@ endif() find_package(catkin REQUIRED COMPONENTS roscpp std_msgs - # mavros_msgs + mavros_msgs sensor_msgs ) diff --git a/include/roscontroller.h b/include/roscontroller.h index ce82fae..2d7c015 100644 --- a/include/roscontroller.h +++ b/include/roscontroller.h @@ -24,8 +24,6 @@ using namespace std; namespace rosbzz_node{ -/*Create node Handler*/ -//ros::NodeHandle n_c; class roscontroller{ @@ -54,7 +52,7 @@ private: ros::Subscriber payload_sub; ros::Subscriber flight_status_sub; /*Commands for flight controller*/ - mavros_msgs::CommandInt cmd_srv; + mavros_msgs::CommandInt cmd_srv; void Initialize_pub_sub(ros::NodeHandle n_c); diff --git a/launch/rosbuzz.launch b/launch/rosbuzz.launch index 05a4870..222f4db 100644 --- a/launch/rosbuzz.launch +++ b/launch/rosbuzz.launch @@ -2,11 +2,11 @@ - + - + diff --git a/src/roscontroller.cpp b/src/roscontroller.cpp index aaec61e..4a71d3d 100644 --- a/src/roscontroller.cpp +++ b/src/roscontroller.cpp @@ -3,12 +3,10 @@ namespace rosbzz_node{ -/*Create node Handler*/ /***Constructor***/ roscontroller::roscontroller(ros::NodeHandle n_c) { - /*Create node Handler*/ ROS_INFO("Buzz_node"); /*Obtain parameters from ros parameter server*/