diff --git a/include/roscontroller.h b/include/roscontroller.h index 1a1c30a..7ce69d8 100644 --- a/include/roscontroller.h +++ b/include/roscontroller.h @@ -148,9 +148,14 @@ private: void Arm(); - void SetMode(); + void SetMode(std::string mode, int delay_miliseconds); + + void SetModeAsync(std::string mode, int delay_miliseconds); + + //void SetModeAsync(std::string mode, int delay); void Subscribe(ros::NodeHandle n_c); + }; } diff --git a/src/roscontroller.cpp b/src/roscontroller.cpp index 389b0f8..30ac680 100644 --- a/src/roscontroller.cpp +++ b/src/roscontroller.cpp @@ -1,4 +1,5 @@ #include "roscontroller.h" +#include namespace rosbzz_node{ @@ -236,10 +237,15 @@ namespace rosbzz_node{ } } - void roscontroller::SetMode(){ + void roscontroller::SetMode(std::string mode, int delay_miliseconds){ + // wait if necessary + if (delay_miliseconds > 0){ + std::this_thread::sleep_for( std::chrono::milliseconds ( delay_miliseconds ) ); + } + // set mode mavros_msgs::SetMode set_mode_message; set_mode_message.request.base_mode = 0; - set_mode_message.request.custom_mode = "GUIDED"; // shit! + set_mode_message.request.custom_mode = mode; if(mode_client.call(set_mode_message)) { ROS_INFO("Service called!"); } else { @@ -247,6 +253,12 @@ namespace rosbzz_node{ } } + //todo: this + void roscontroller::SetModeAsync(std::string mode, int delay_miliseconds){ + std::thread([&](){SetMode(mode, delay_miliseconds);}).detach(); + cout << "Async call called... " < ..." -include "/home/ubuntu/buzz/src/include/vec2.bzz" +include "/home/ivan/dev/buzz/src/include/vec2.bzz" #################################################################################################### # Updater related # This should be here for the updater to work, changing position of code will crash the updater