diff --git a/include/roscontroller.h b/include/roscontroller.h index 7ce69d8..fbf3d6d 100644 --- a/include/roscontroller.h +++ b/include/roscontroller.h @@ -11,6 +11,8 @@ #include "mavros_msgs/State.h" #include "mavros_msgs/BatteryStatus.h" #include "mavros_msgs/Mavlink.h" +#include "mavros_msgs/WaypointPush.h" +#include "mavros_msgs/Waypoint.h" #include "sensor_msgs/NavSatStatus.h" #include #include @@ -81,6 +83,8 @@ private: mavros_msgs::SetMode m_cmdSetMode; ros::ServiceClient mode_client; + ros::ServiceClient mission_client; + void Initialize_pub_sub(ros::NodeHandle n_c); /*Obtain data from ros parameter server*/ @@ -156,6 +160,8 @@ private: void Subscribe(ros::NodeHandle n_c); + void WaypointMissionSetup(); + }; } diff --git a/launch/rosbuzz.launch b/launch/rosbuzz.launch index eb901e7..47f5a0f 100644 --- a/launch/rosbuzz.launch +++ b/launch/rosbuzz.launch @@ -3,7 +3,7 @@ - + diff --git a/src/roscontroller.cpp b/src/roscontroller.cpp index 30ac680..07d337f 100644 --- a/src/roscontroller.cpp +++ b/src/roscontroller.cpp @@ -177,6 +177,7 @@ namespace rosbzz_node{ neigh_pos_pub = n_c.advertise("/neighbours_pos",1000); /* Service Clients*/ arm_client = n_c.serviceClient(armclient); + mission_client = n_c.serviceClient("/mavros/mission/push"); mode_client = n_c.serviceClient(modeclient); mav_client = n_c.serviceClient(fcclient_name); @@ -237,6 +238,29 @@ namespace rosbzz_node{ } } + void roscontroller::WaypointMissionSetup(){ + mavros_msgs::WaypointPush srv; + mavros_msgs::Waypoint waypoint; + + // prepare waypoint mission package + waypoint.frame = mavros_msgs::Waypoint::FRAME_GLOBAL; + waypoint.command = mavros_msgs::CommandCode::NAV_WAYPOINT; + waypoint.is_current = 2; // IMPORTANT: goto is no longer used, so instead, use magic number 2 for is_current parameter + waypoint.autocontinue = 0; + waypoint.x_lat = 45.507730f; + waypoint.y_long = -73.613961f; + //45.507730, -73.613961 + waypoint.z_alt = 10; + + srv.request.waypoints.push_back(waypoint); + if(mission_client.call(srv)){ + ROS_INFO("Mission service called!"); + } else { + ROS_INFO("Mission service failed!"); + } + + } + void roscontroller::SetMode(std::string mode, int delay_miliseconds){ // wait if necessary if (delay_miliseconds > 0){ @@ -588,7 +612,7 @@ namespace rosbzz_node{ buzzuav_closures::flight_status_update(1); else if (msg->mode == "LAND") buzzuav_closures::flight_status_update(4); - else // ground standby = LOITER? + else buzzuav_closures::flight_status_update(1);//? } @@ -708,8 +732,9 @@ namespace rosbzz_node{ rc_cmd=mavros_msgs::CommandCode::NAV_TAKEOFF; /* arming */ SetMode("GUIDED", 0); - cout<< "this..."< ..." -include "/home/ivan/dev/buzz/src/include/vec2.bzz" +include "/home/ubuntu/buzz/src/include/vec2.bzz" #################################################################################################### # Updater related # This should be here for the updater to work, changing position of code will crash the updater