DroneNode.cpp
Go to the documentation of this file.
1 /*
2 BSD 2-Clause License
3 
4 Copyright (c) 2019, Simranjeet Singh
5 All rights reserved.
6 
7 Redistribution and use in source and binary forms, with or without
8 modification, are permitted provided that the following conditions are met:
9 
10 1. Redistributions of source code must retain the above copyright notice, this
11  list of conditions and the following disclaimer.
12 
13 2. Redistributions in binary form must reproduce the above copyright notice,
14  this list of conditions and the following disclaimer in the documentation
15  and/or other materials provided with the distribution.
16 
17 THIS SOFTWARE IS PROVIDED BY THE COPYRIGHT HOLDERS AND CONTRIBUTORS "AS IS"
18 AND ANY EXPRESS OR IMPLIED WARRANTIES, INCLUDING, BUT NOT LIMITED TO, THE
19 IMPLIED WARRANTIES OF MERCHANTABILITY AND FITNESS FOR A PARTICULAR PURPOSE ARE
20 DISCLAIMED. IN NO EVENT SHALL THE COPYRIGHT HOLDER OR CONTRIBUTORS BE LIABLE
21 FOR ANY DIRECT, INDIRECT, INCIDENTAL, SPECIAL, EXEMPLARY, OR CONSEQUENTIAL
22 DAMAGES (INCLUDING, BUT NOT LIMITED TO, PROCUREMENT OF SUBSTITUTE GOODS OR
23 SERVICES; LOSS OF USE, DATA, OR PROFITS; OR BUSINESS INTERRUPTION) HOWEVER
24 CAUSED AND ON ANY THEORY OF LIABILITY, WHETHER IN CONTRACT, STRICT LIABILITY,
25 OR TORT (INCLUDING NEGLIGENCE OR OTHERWISE) ARISING IN ANY WAY OUT OF THE USE
26 OF THIS SOFTWARE, EVEN IF ADVISED OF THE POSSIBILITY OF SUCH DAMAGE.
27 */
28 
29 #include <ros/ros.h>
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>
34 #include <sys/time.h>
35 #include <boost/thread.hpp>
36 #include <boost/chrono.hpp>
37 #include <pthread.h>
38 #include <unistd.h>
39 #include <eyantra_drone/Common.h>
40 #include <eyantra_drone/Protocol.h>
41 #include <edrone_client/edrone_msgs.h>
42 
43 #define PORT 23
44 
45 using namespace std;
46 
47 bool isSocketCreate=false;
48 
51 
53 edrone_client::edrone_services service;
54 
55 int userRC[8]={1500,1500,1500,1500,1000,1000,1000,1000};
56 
57 void *createSocket(void *threadid){
59  pthread_exit(NULL);
60 };
61 
62 void *writeFunction(void *threadid){
63  std::vector<int> requests;
64  requests.push_back(MSP_RC);
65  requests.push_back(MSP_ATTITUDE);
66  requests.push_back(MSP_RAW_IMU);
67  requests.push_back(MSP_ALTITUDE);
68  requests.push_back(MSP_ANALOG);
69 
70 
71  while(1)
72  {
74  pro.sendRequestMSP_GET_DEBUG(requests);
75  usleep(22000);
76  }
77  pthread_exit(NULL);
78 }
79 
80 void *readFunction(void *threadid){
81  do
82  {
83  com.readFrame();
84  //usleep(5);
85  }
86  while(1);
87  pthread_exit(NULL);
88 }
89 
90 void *serviceFunction(void *threadid){
91  while (1)
92  {
93  if (serviceClient.call(service))
94  {
95 
96  service.request.accX=accX;
97  service.request.accY=accY;
98  service.request.accZ=accZ;
99  service.request.gyroX=gyroX;
100  service.request.gyroY=gyroY;
101  service.request.gyroZ=gyroZ;
102  service.request.magX=magX;
103  service.request.magY=magY;
104  service.request.magZ=magZ;
105  service.request.roll=roll;
106  service.request.pitch=pitch;
107  service.request.yaw=yaw;
108  service.request.alt=alt;
109  service.request.battery=battery;
110  service.request.rssi=rssi;
111  }
112  }
113  pthread_exit(NULL);
114 }
115 
116 void Callback(const edrone_client::edrone_msgs::ConstPtr& msg){
117  userRC[0] = msg->rcRoll;
118  userRC[1] = msg->rcPitch;
119  userRC[2] = msg->rcThrottle;
120  userRC[3] = msg->rcYaw;
121  userRC[4] = msg->rcAUX1;
122  userRC[5] = msg->rcAUX2;
123  userRC[6] = msg->rcAUX3;
124  userRC[7] = msg->rcAUX4;
125  // cout << "roll = " << userRC[0] << "pitch = " <<userRC[1] << "Throttle = "<< userRC[2] << endl;
126 }
127 
128 int main(int argc, char **argv){
129  pthread_t thread, readThread, writeThread, serviceThread;
130  int rc;
131  ros::init(argc, argv, "DroneNode");
132  ros::NodeHandle n;
133  ros::Subscriber sub = n.subscribe("drone_command", 1000, Callback);
134  rc = pthread_create(&thread, NULL, createSocket, (void *)1);
135  if (rc)
136  {
137  cout << "Error:unable to create communication thread," << rc << endl;
138  exit(-1);
139  }
140  pthread_join( thread, NULL);
141 
142  if(isSocketCreate)
143  {
144  //cout << "main() : creating write thread, " << i << endl;
145  rc = pthread_create(&writeThread, NULL, writeFunction, (void *)2);
146  if (rc)
147  {
148  cout << "Error:unable to create write thread," << rc << endl;
149  exit(-1);
150  }
151  // cout << "main() : creating read thread, " << i << endl;
152  rc = pthread_create(&readThread, NULL, readFunction, (void *)3);
153  if (rc)
154  {
155  cout << "Error:unable to read create thread," << rc << endl;
156  exit(-1);
157  }
158 
159  serviceClient = n.serviceClient<edrone_client::edrone_services>("eDroneService",true);
160  //cout << "main() : creating service thread, " << i << endl;
161  rc = pthread_create(&serviceThread, NULL, serviceFunction, (void *)4);
162 
163  if (rc)
164  {
165  cout << "Error:unable to service create thread," << rc << endl;
166  exit(-1);
167  }
168  }
169 
170  ros::spin();
171  return 0;
172 }
void * createSocket(void *threadid)
Definition: DroneNode.cpp:57
int userRC[8]
Definition: DroneNode.cpp:55
ServiceClient serviceClient(const std::string &service_name, bool persistent=false, const M_string &header_values=M_string())
void * writeFunction(void *threadid)
Definition: DroneNode.cpp:62
void * readFunction(void *threadid)
Definition: DroneNode.cpp:80
static const int MSP_ATTITUDE
Definition: Protocol.h:43
edrone_client::edrone_services service
Definition: DroneNode.cpp:53
bool isSocketCreate
Definition: DroneNode.cpp:47
Subscriber subscribe(const std::string &topic, uint32_t queue_size, void(T::*fp)(M), T *obj, const TransportHints &transport_hints=TransportHints())
int rssi
Definition: Protocol.cpp:44
float gyroY
Definition: Protocol.cpp:49
float accZ
Definition: Protocol.cpp:47
ROSCPP_DECL void init(int &argc, char **argv, const std::string &name, uint32_t options=0)
bool call(MReq &req, MRes &res)
float accY
Definition: Protocol.cpp:46
int pitch
Definition: Protocol.cpp:41
float gyroZ
Definition: Protocol.cpp:50
ROSCPP_DECL void spin(Spinner &spinner)
int main(int argc, char **argv)
Definition: DroneNode.cpp:128
static const int MSP_RC
Definition: Protocol.h:42
void sendRequestMSP_GET_DEBUG(std::vector< int > requests)
Definition: Protocol.cpp:246
static const int MSP_ALTITUDE
Definition: Protocol.h:44
void * serviceFunction(void *threadid)
Definition: DroneNode.cpp:90
Communication com
Definition: DroneNode.cpp:49
Protocol pro
Definition: DroneNode.cpp:50
int roll
Definition: Protocol.cpp:40
float battery
Definition: Protocol.cpp:43
void Callback(const edrone_client::edrone_msgs::ConstPtr &msg)
Definition: DroneNode.cpp:116
float alt
Definition: Protocol.cpp:54
sensor_msgs::ImagePtr msg
Definition: DroneCam.cpp:56
float magY
Definition: Protocol.cpp:52
float magZ
Definition: Protocol.cpp:53
ros::ServiceClient serviceClient
Definition: DroneNode.cpp:52
float magX
Definition: Protocol.cpp:51
static const int MSP_ANALOG
Definition: Protocol.h:45
float accX
Definition: Protocol.cpp:45
static const int MSP_RAW_IMU
Definition: Protocol.h:41
float gyroX
Definition: Protocol.cpp:48
void sendRequestMSP_SET_RAW_RC(int channels[])
Definition: Protocol.cpp:197
int yaw
Definition: Protocol.cpp:42


edrone_client
Author(s): Simranjeet Singh
autogenerated on Sun Dec 1 2019 03:30:51