30 #include <std_msgs/String.h> 31 #include <std_msgs/Float64.h> 32 #include <edrone_client/edrone_services.h> 33 #include <geometry_msgs/PoseArray.h> 35 #include <boost/thread.hpp> 36 #include <boost/chrono.hpp> 41 #include <edrone_client/edrone_msgs.h> 55 int userRC[8]={1500,1500,1500,1500,1000,1000,1000,1000};
63 std::vector<int> requests;
64 requests.push_back(
MSP_RC);
119 userRC[2] = msg->rcThrottle;
128 int main(
int argc,
char **argv){
129 pthread_t thread, readThread, writeThread, serviceThread;
134 rc = pthread_create(&thread, NULL,
createSocket, (
void *)1);
137 cout <<
"Error:unable to create communication thread," << rc << endl;
140 pthread_join( thread, NULL);
145 rc = pthread_create(&writeThread, NULL,
writeFunction, (
void *)2);
148 cout <<
"Error:unable to create write thread," << rc << endl;
152 rc = pthread_create(&readThread, NULL,
readFunction, (
void *)3);
155 cout <<
"Error:unable to read create thread," << rc << endl;
159 serviceClient = n.
serviceClient<edrone_client::edrone_services>(
"eDroneService",
true);
165 cout <<
"Error:unable to service create thread," << rc << endl;
void * createSocket(void *threadid)
ServiceClient serviceClient(const std::string &service_name, bool persistent=false, const M_string &header_values=M_string())
void * writeFunction(void *threadid)
void * readFunction(void *threadid)
static const int MSP_ATTITUDE
edrone_client::edrone_services service
Subscriber subscribe(const std::string &topic, uint32_t queue_size, void(T::*fp)(M), T *obj, const TransportHints &transport_hints=TransportHints())
ROSCPP_DECL void init(int &argc, char **argv, const std::string &name, uint32_t options=0)
bool call(MReq &req, MRes &res)
ROSCPP_DECL void spin(Spinner &spinner)
int main(int argc, char **argv)
void sendRequestMSP_GET_DEBUG(std::vector< int > requests)
static const int MSP_ALTITUDE
void * serviceFunction(void *threadid)
void Callback(const edrone_client::edrone_msgs::ConstPtr &msg)
sensor_msgs::ImagePtr msg
ros::ServiceClient serviceClient
static const int MSP_ANALOG
static const int MSP_RAW_IMU
void sendRequestMSP_SET_RAW_RC(int channels[])