30 #include <std_msgs/String.h> 31 #include <edrone_client/edrone_services.h> 32 #include <geometry_msgs/PoseArray.h> 34 #include <boost/thread.hpp> 35 #include <boost/chrono.hpp> 40 #include <edrone_client/edrone_msgs.h> 56 edrone_client::edrone_services
service[2];
59 int userRC[9]={1500,1500,1500,1500,1000,1000,1000,1000,0};
80 std::vector<int> requests;
81 requests.push_back(
MSP_RC);
144 userRC[2] = msg->rcThrottle;
150 userRC[8] = msg->droneIndex;
154 int main(
int argc,
char **argv){
159 all_ips.push_back(
"192.168.43.151");
169 char topic_name[] =
"drone_command/ ";
170 char service_name[] =
"droneService ";
187 for(i = 0; i <
all_ips.size(); i++){
191 topic_name[strlen(topic_name)-1] = 0x30+
i;
193 service_name[strlen(service_name)-1] = 0x30+
i;
205 rc = pthread_create(&tds[i], NULL,
createSocket, (
void *) &ipStructVar);
208 cout <<
"Error:unable to create communication thread," << rc << endl;
212 pthread_join( tds[i], NULL);
216 rc = pthread_create(&wds[i], NULL,
writeFunction, (
void *)2);
219 cout <<
"Error:unable to create write thread," << rc << endl;
225 rc = pthread_create(&rds[i], NULL,
readMulFunction, (
void *) &ipStructVar);
229 cout <<
"Error:unable to read create thread," << rc << endl;
235 serviceClient = n.
serviceClient<edrone_client::edrone_services>(service_name,
true);
236 rc = pthread_create(&sds[i], NULL,
serviceFunction, (
void *) &ipStructVar);
240 cout <<
"Error:unable to service create thread," << rc << endl;
ServiceClient serviceClient(const std::string &service_name, bool persistent=false, const M_string &header_values=M_string())
ros::ServiceClient serviceClient
static const int MSP_ATTITUDE
edrone_client::edrone_services service[2]
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)
void * writeFunction(void *threadid)
void sendMulRequestMSP_SET_RAW_RC(int channels[])
ROSCPP_DECL void spin(Spinner &spinner)
void * readFunction(void *threadid)
static const int MSP_ALTITUDE
int main(int argc, char **argv)
void readMulFrame(int index)
void sendMulRequestMSP_GET_DEBUG(std::vector< int > requests, int index)
sensor_msgs::ImagePtr msg
bool connectMulSock(const std::string &ip, int index)
void * readMulFunction(void *arg)
void * serviceFunction(void *arg)
void * createSocket(void *arg)
static const int MSP_RAW_IMU
void Callback(const edrone_client::edrone_msgs::ConstPtr &msg)