an_driver.cpp
Go to the documentation of this file.
1 /****************************************************************/
2 /* */
3 /* Advanced Navigation Packet Protocol Library */
4 /* ROS Driver, Packet to Published Message Example */
5 /* Copyright 2017, Advanced Navigation Pty Ltd */
6 /* */
7 /****************************************************************/
8 /*
9  *
10  * Permission is hereby granted, free of charge, to any person obtaining
11  * a copy of this software and associated documentation files (the "Software"),
12  * to deal in the Software without restriction, including without limitation
13  * the rights to use, copy, modify, merge, publish, distribute, sublicense,
14  * and/or sell copies of the Software, and to permit persons to whom the
15  * Software is furnished to do so, subject to the following conditions:
16  *
17  * The above copyright notice and this permission notice shall be included
18  * in all copies or substantial portions of the Software.
19  *
20  * THE SOFTWARE IS PROVIDED "AS IS", WITHOUT WARRANTY OF ANY KIND, EXPRESS
21  * OR IMPLIED, INCLUDING BUT NOT LIMITED TO THE WARRANTIES OF MERCHANTABILITY,
22  * FITNESS FOR A PARTICULAR PURPOSE AND NONINFRINGEMENT. IN NO EVENT SHALL THE
23  * AUTHORS OR COPYRIGHT HOLDERS BE LIABLE FOR ANY CLAIM, DAMAGES OR OTHER
24  * LIABILITY, WHETHER IN AN ACTION OF CONTRACT, TORT OR OTHERWISE, ARISING
25  * FROM, OUT OF OR IN CONNECTION WITH THE SOFTWARE OR THE USE OR OTHER
26  * DEALINGS IN THE SOFTWARE.
27  */
28 
29 #include <ros/ros.h>
30 #include <stdlib.h>
31 #include <stdio.h>
32 #include <stdint.h>
33 #include <math.h>
34 #include <unistd.h>
35 
36 #include "rs232/rs232.h"
37 #include "an_packet_protocol.h"
38 #include "spatial_packets.h"
39 
40 #include <sensor_msgs/NavSatFix.h>
41 #include <sensor_msgs/TimeReference.h>
42 #include <sensor_msgs/Imu.h>
43 #include <geometry_msgs/Twist.h>
44 #include <diagnostic_msgs/DiagnosticArray.h>
45 
46 #define RADIANS_TO_DEGREES (180.0/M_PI)
47 
48 int main(int argc, char *argv[]) {
49  // Set up ROS node //
50  ros::init(argc, argv, "an_device_node");
51  ros::NodeHandle nh;
52  ros::NodeHandle pnh("~");
53 
54  printf("\nYour Advanced Navigation ROS driver is currently running\nPress Ctrl-C to interrupt\n");
55 
56  // Set up the COM port
57  std::string com_port;
58  int baud_rate;
59  std::string imu_frame_id;
60  std::string nav_sat_frame_id;
61  std::string topic_prefix;
62 
63  if (argc >= 3) {
64  com_port = std::string(argv[1]);
65  baud_rate = atoi(argv[2]);
66  }
67  else {
68  pnh.param("port", com_port, std::string("/dev/ttyUSB0"));
69  pnh.param("baud_rate", baud_rate, 115200);
70  }
71 
72  pnh.param("imu_frame_id", imu_frame_id, std::string("imu"));
73  pnh.param("nav_sat_frame_id", nav_sat_frame_id, std::string("gps"));
74  pnh.param("topic_prefix", topic_prefix, std::string("an_device"));
75 
76  // Initialise Publishers and Topics //
77  ros::Publisher nav_sat_fix_pub=nh.advertise<sensor_msgs::NavSatFix>(topic_prefix + "/NavSatFix",10);
78  ros::Publisher twist_pub=nh.advertise<geometry_msgs::Twist>(topic_prefix + "/Twist",10);
79  ros::Publisher imu_pub=nh.advertise<sensor_msgs::Imu>(topic_prefix + "/Imu",10);
80  ros::Publisher system_status_pub=nh.advertise<diagnostic_msgs::DiagnosticStatus>(topic_prefix + "/SystemStatus",10);
81  ros::Publisher filter_status_pub=nh.advertise<diagnostic_msgs::DiagnosticStatus>(topic_prefix + "/FilterStatus",10);
82 
83  // Initialise messages
84  sensor_msgs::NavSatFix nav_sat_fix_msg;
85  nav_sat_fix_msg.header.stamp.sec=0;
86  nav_sat_fix_msg.header.stamp.nsec=0;
87  nav_sat_fix_msg.header.frame_id='0';
88  nav_sat_fix_msg.status.status=0;
89  nav_sat_fix_msg.status.service=1; // fixed to GPS
90  nav_sat_fix_msg.latitude=0.0;
91  nav_sat_fix_msg.longitude=0.0;
92  nav_sat_fix_msg.altitude=0.0;
93  nav_sat_fix_msg.position_covariance={0.0,0.0,0.0,0.0,0.0,0.0,0.0,0.0,0.0};
94  nav_sat_fix_msg.position_covariance_type=2; // fixed to variance on the diagonal
95 
96  geometry_msgs::Twist twist_msg;
97  twist_msg.linear.x=0.0;
98  twist_msg.linear.y=0.0;
99  twist_msg.linear.z=0.0;
100  twist_msg.angular.x=0.0;
101  twist_msg.angular.y=0.0;
102  twist_msg.angular.z=0.0;
103 
104  sensor_msgs::Imu imu_msg;
105  imu_msg.header.stamp.sec=0;
106  imu_msg.header.stamp.nsec=0;
107  imu_msg.header.frame_id='0';
108  imu_msg.orientation.x=0.0;
109  imu_msg.orientation.y=0.0;
110  imu_msg.orientation.z=0.0;
111  imu_msg.orientation.w=0.0;
112  imu_msg.orientation_covariance={0.0,0.0,0.0,0.0,0.0,0.0,0.0,0.0,0.0};
113  imu_msg.angular_velocity.x=0.0;
114  imu_msg.angular_velocity.y=0.0;
115  imu_msg.angular_velocity.z=0.0;
116  imu_msg.angular_velocity_covariance={0.0,0.0,0.0,0.0,0.0,0.0,0.0,0.0,0.0}; // fixed
117  imu_msg.linear_acceleration.x=0.0;
118  imu_msg.linear_acceleration.y=0.0;
119  imu_msg.linear_acceleration.z=0.0;
120  imu_msg.linear_acceleration_covariance={0.0,0.0,0.0,0.0,0.0,0.0,0.0,0.0,0.0}; // fixed
121 
122  diagnostic_msgs::DiagnosticStatus system_status_msg;
123  system_status_msg.level = 0; // default OK state
124  system_status_msg.name = "System Status";
125  system_status_msg.message = "";
126 
127  diagnostic_msgs::DiagnosticStatus filter_status_msg;
128  filter_status_msg.level = 0; // default OK state
129  filter_status_msg.name = "Filter Status";
130  filter_status_msg.message = "";
131 
132  // get data from com port //
133  an_decoder_t an_decoder;
134  an_packet_t *an_packet;
135  system_state_packet_t system_state_packet;
136  quaternion_orientation_standard_deviation_packet_t quaternion_orientation_standard_deviation_packet;
137  int bytes_received;
138 
139  if (OpenComport(const_cast<char*>(com_port.c_str()), baud_rate))
140  {
141  printf("Could not open serial port: %s \n",com_port.c_str());
142  exit(EXIT_FAILURE);
143  }
144 
145  an_decoder_initialise(&an_decoder);
146 
147  // Loop continuously, polling for packets
148  while (ros::ok())
149  {
150  ros::spinOnce();
151  if ((bytes_received = PollComport(an_decoder_pointer(&an_decoder), an_decoder_size(&an_decoder))) > 0)
152  {
153  // increment the decode buffer length by the number of bytes received //
154  an_decoder_increment(&an_decoder, bytes_received);
155 
156  // decode all the packets in the buffer //
157  while ((an_packet = an_packet_decode(&an_decoder)) != NULL)
158  {
159  // system state packet //
160  if (an_packet->id == packet_id_system_state)
161  {
162  if(decode_system_state_packet(&system_state_packet, an_packet) == 0)
163  {
164  // NavSatFix
165  nav_sat_fix_msg.header.stamp.sec=system_state_packet.unix_time_seconds;
166  nav_sat_fix_msg.header.stamp.nsec=system_state_packet.microseconds*1000;
167  nav_sat_fix_msg.header.frame_id=nav_sat_frame_id;
168  if ((system_state_packet.filter_status.b.gnss_fix_type == 1) ||
169  (system_state_packet.filter_status.b.gnss_fix_type == 2))
170  {
171  nav_sat_fix_msg.status.status=0;
172  }
173  else if ((system_state_packet.filter_status.b.gnss_fix_type == 3) ||
174  (system_state_packet.filter_status.b.gnss_fix_type == 5))
175  {
176  nav_sat_fix_msg.status.status=1;
177  }
178  else if ((system_state_packet.filter_status.b.gnss_fix_type == 4) ||
179  (system_state_packet.filter_status.b.gnss_fix_type == 6) ||
180  (system_state_packet.filter_status.b.gnss_fix_type == 7))
181  {
182  nav_sat_fix_msg.status.status=2;
183  }
184  else
185  {
186  nav_sat_fix_msg.status.status=-1;
187  }
188  nav_sat_fix_msg.latitude=system_state_packet.latitude * RADIANS_TO_DEGREES;
189  nav_sat_fix_msg.longitude=system_state_packet.longitude * RADIANS_TO_DEGREES;
190  nav_sat_fix_msg.altitude=system_state_packet.height;
191  nav_sat_fix_msg.position_covariance={pow(system_state_packet.standard_deviation[1],2), 0.0, 0.0,
192  0.0, pow(system_state_packet.standard_deviation[0],2), 0.0,
193  0.0, 0.0, pow(system_state_packet.standard_deviation[2],2)};
194 
195  // Twist
196  twist_msg.linear.x=system_state_packet.velocity[0];
197  twist_msg.linear.y=system_state_packet.velocity[1];
198  twist_msg.linear.z=system_state_packet.velocity[2];
199  twist_msg.angular.x=system_state_packet.angular_velocity[0];
200  twist_msg.angular.y=system_state_packet.angular_velocity[1];
201  twist_msg.angular.z=system_state_packet.angular_velocity[2];
202 
203  // IMU
204  imu_msg.header.stamp.sec=system_state_packet.unix_time_seconds;
205  imu_msg.header.stamp.nsec=system_state_packet.microseconds*1000;
206  imu_msg.header.frame_id=imu_frame_id;
207  // Convert roll, pitch, yaw from radians to quaternion format //
208  float phi = system_state_packet.orientation[0] / 2.0f;
209  float theta = system_state_packet.orientation[1] / 2.0f;
210  float psi = system_state_packet.orientation[2] / 2.0f;
211  float sin_phi = sinf(phi);
212  float cos_phi = cosf(phi);
213  float sin_theta = sinf(theta);
214  float cos_theta = cosf(theta);
215  float sin_psi = sinf(psi);
216  float cos_psi = cosf(psi);
217  imu_msg.orientation.x=-cos_phi * sin_theta * sin_psi + sin_phi * cos_theta * cos_psi;
218  imu_msg.orientation.y=cos_phi * sin_theta * cos_psi + sin_phi * cos_theta * sin_psi;
219  imu_msg.orientation.z=cos_phi * cos_theta * sin_psi - sin_phi * sin_theta * cos_psi;
220  imu_msg.orientation.w=cos_phi * cos_theta * cos_psi + sin_phi * sin_theta * sin_psi;
221 
222  imu_msg.angular_velocity.x=system_state_packet.angular_velocity[0]; // These the same as the TWIST msg values
223  imu_msg.angular_velocity.y=system_state_packet.angular_velocity[1];
224  imu_msg.angular_velocity.z=system_state_packet.angular_velocity[2];
225  imu_msg.linear_acceleration.x=system_state_packet.body_acceleration[0];
226  imu_msg.linear_acceleration.y=system_state_packet.body_acceleration[1];
227  imu_msg.linear_acceleration.z=system_state_packet.body_acceleration[2];
228 
229  // System Status
230  system_status_msg.message = "";
231  system_status_msg.level = 0; // default OK state
232  if (system_state_packet.system_status.b.system_failure) {
233  system_status_msg.level = 2; // ERROR state
234  system_status_msg.message = system_status_msg.message + "0. System Failure! ";
235  }
236  if (system_state_packet.system_status.b.accelerometer_sensor_failure) {
237  system_status_msg.level = 2; // ERROR state
238  system_status_msg.message = system_status_msg.message + "1. Accelerometer Sensor Failure! ";
239  }
240  if (system_state_packet.system_status.b.gyroscope_sensor_failure) {
241  system_status_msg.level = 2; // ERROR state
242  system_status_msg.message = system_status_msg.message + "2. Gyroscope Sensor Failure! ";
243  }
244  if (system_state_packet.system_status.b.magnetometer_sensor_failure) {
245  system_status_msg.level = 2; // ERROR state
246  system_status_msg.message = system_status_msg.message + "3. Magnetometer Sensor Failure! ";
247  }
248  if (system_state_packet.system_status.b.pressure_sensor_failure) {
249  system_status_msg.level = 2; // ERROR state
250  system_status_msg.message = system_status_msg.message + "4. Pressure Sensor Failure! ";
251  }
252  if (system_state_packet.system_status.b.gnss_failure) {
253  system_status_msg.level = 2; // ERROR state
254  system_status_msg.message = system_status_msg.message + "5. GNSS Failure! ";
255  }
256  if (system_state_packet.system_status.b.accelerometer_over_range) {
257  system_status_msg.level = 2; // ERROR state
258  system_status_msg.message = system_status_msg.message + "6. Accelerometer Over Range! ";
259  }
260  if (system_state_packet.system_status.b.gyroscope_over_range) {
261  system_status_msg.level = 2; // ERROR state
262  system_status_msg.message = system_status_msg.message + "7. Gyroscope Over Range! ";
263  }
264  if (system_state_packet.system_status.b.magnetometer_over_range) {
265  system_status_msg.level = 2; // ERROR state
266  system_status_msg.message = system_status_msg.message + "8. Magnetometer Over Range! ";
267  }
268  if (system_state_packet.system_status.b.pressure_over_range) {
269  system_status_msg.level = 2; // ERROR state
270  system_status_msg.message = system_status_msg.message + "9. Pressure Over Range! ";
271  }
272  if (system_state_packet.system_status.b.minimum_temperature_alarm) {
273  system_status_msg.level = 2; // ERROR state
274  system_status_msg.message = system_status_msg.message + "10. Minimum Temperature Alarm! ";
275  }
276  if (system_state_packet.system_status.b.maximum_temperature_alarm) {
277  system_status_msg.level = 2; // ERROR state
278  system_status_msg.message = system_status_msg.message + "11. Maximum Temperature Alarm! ";
279  }
280  if (system_state_packet.system_status.b.low_voltage_alarm) {
281  system_status_msg.level = 2; // ERROR state
282  system_status_msg.message = system_status_msg.message + "12. Low Voltage Alarm! ";
283  }
284  if (system_state_packet.system_status.b.high_voltage_alarm) {
285  system_status_msg.level = 2; // ERROR state
286  system_status_msg.message = system_status_msg.message + "13. High Voltage Alarm! ";
287  }
288  if (system_state_packet.system_status.b.gnss_antenna_disconnected) {
289  system_status_msg.level = 2; // ERROR state
290  system_status_msg.message = system_status_msg.message + "14. GNSS Antenna Disconnected! ";
291  }
292  if (system_state_packet.system_status.b.serial_port_overflow_alarm) {
293  system_status_msg.level = 2; // ERROR state
294  system_status_msg.message = system_status_msg.message + "15. Data Output Overflow Alarm! ";
295  }
296 
297  // Filter Status
298  filter_status_msg.message = "";
299  filter_status_msg.level = 0; // default OK state
300  if (system_state_packet.filter_status.b.orientation_filter_initialised) {
301  filter_status_msg.message = filter_status_msg.message + "0. Orientation Filter Initialised. ";
302  }
303  else {
304  filter_status_msg.level = 1; // WARN state
305  filter_status_msg.message = filter_status_msg.message + "0. Orientation Filter NOT Initialised. ";
306  }
307  if (system_state_packet.filter_status.b.ins_filter_initialised) {
308  filter_status_msg.message = filter_status_msg.message + "1. Navigation Filter Initialised. ";
309  }
310  else {
311  filter_status_msg.level = 1; // WARN state
312  filter_status_msg.message = filter_status_msg.message + "1. Navigation Filter NOT Initialised. ";
313  }
314  if (system_state_packet.filter_status.b.heading_initialised) {
315  filter_status_msg.message = filter_status_msg.message + "2. Heading Initialised. ";
316  }
317  else {
318  filter_status_msg.level = 1; // WARN state
319  filter_status_msg.message = filter_status_msg.message + "2. Heading NOT Initialised. ";
320  }
321  if (system_state_packet.filter_status.b.utc_time_initialised) {
322  filter_status_msg.message = filter_status_msg.message + "3. UTC Time Initialised. ";
323  }
324  else {
325  filter_status_msg.level = 1; // WARN state
326  filter_status_msg.message = filter_status_msg.message + "3. UTC Time NOT Initialised. ";
327  }
328  if (system_state_packet.filter_status.b.event1_flag) {
329  filter_status_msg.level = 1; // WARN state
330  filter_status_msg.message = filter_status_msg.message + "7. Event 1 Occured. ";
331  }
332  else {
333  filter_status_msg.message = filter_status_msg.message + "7. Event 1 NOT Occured. ";
334  }
335  if (system_state_packet.filter_status.b.event2_flag) {
336  filter_status_msg.level = 1; // WARN state
337  filter_status_msg.message = filter_status_msg.message + "8. Event 2 Occured. ";
338  }
339  else {
340  filter_status_msg.message = filter_status_msg.message + "8. Event 2 NOT Occured. ";
341  }
342  if (system_state_packet.filter_status.b.internal_gnss_enabled) {
343  filter_status_msg.message = filter_status_msg.message + "9. Internal GNSS Enabled. ";
344  }
345  else {
346  filter_status_msg.level = 1; // WARN state
347  filter_status_msg.message = filter_status_msg.message + "9. Internal GNSS NOT Enabled. ";
348  }
349  if (system_state_packet.filter_status.b.magnetic_heading_enabled) {
350  filter_status_msg.message = filter_status_msg.message + "10. Magnetic Heading Active. ";
351  }
352  else {
353  filter_status_msg.level = 1; // WARN state
354  filter_status_msg.message = filter_status_msg.message + "10. Magnetic Heading NOT Active. ";
355  }
356  if (system_state_packet.filter_status.b.velocity_heading_enabled) {
357  filter_status_msg.message = filter_status_msg.message + "11. Velocity Heading Enabled. ";
358  }
359  else {
360  filter_status_msg.level = 1; // WARN state
361  filter_status_msg.message = filter_status_msg.message + "11. Velocity Heading NOT Enabled. ";
362  }
363  if (system_state_packet.filter_status.b.atmospheric_altitude_enabled) {
364  filter_status_msg.message = filter_status_msg.message + "12. Atmospheric Altitude Enabled. ";
365  }
366  else {
367  filter_status_msg.message = filter_status_msg.message + "12. Atmospheric Altitude NOT Enabled. ";
368  filter_status_msg.level = 1; // WARN state
369  }
370  if (system_state_packet.filter_status.b.external_position_active) {
371  filter_status_msg.message = filter_status_msg.message + "13. External Position Active. ";
372  }
373  else {
374  filter_status_msg.level = 1; // WARN state
375  filter_status_msg.message = filter_status_msg.message + "13. External Position NOT Active. ";
376  }
377  if (system_state_packet.filter_status.b.external_velocity_active) {
378  filter_status_msg.message = filter_status_msg.message + "14. External Velocity Active. ";
379  }
380  else {
381  filter_status_msg.level = 1; // WARN state
382  filter_status_msg.message = filter_status_msg.message + "14. External Velocity NOT Active. ";
383  }
384  if (system_state_packet.filter_status.b.external_heading_active) {
385  filter_status_msg.message = filter_status_msg.message + "15. External Heading Active. ";
386  }
387  else {
388  filter_status_msg.level = 1; // WARN state
389  filter_status_msg.message = filter_status_msg.message + "15. External Heading NOT Active. ";
390  }
391  }
392  }
393 
394  // quaternion orientation standard deviation packet //
396  {
397  // copy all the binary data into the typedef struct for the packet //
398  // this allows easy access to all the different values //
399  if(decode_quaternion_orientation_standard_deviation_packet(&quaternion_orientation_standard_deviation_packet, an_packet) == 0)
400  {
401  // IMU
402  imu_msg.orientation_covariance[0] = quaternion_orientation_standard_deviation_packet.standard_deviation[0];
403  imu_msg.orientation_covariance[4] = quaternion_orientation_standard_deviation_packet.standard_deviation[1];
404  imu_msg.orientation_covariance[8] = quaternion_orientation_standard_deviation_packet.standard_deviation[2];
405  }
406  }
407  // Ensure that you free the an_packet when your done with it //
408  // or you will leak memory //
409  an_packet_free(&an_packet);
410 
411  // Publish messages //
412  nav_sat_fix_pub.publish(nav_sat_fix_msg);
413  twist_pub.publish(twist_msg);
414  imu_pub.publish(imu_msg);
415  system_status_pub.publish(system_status_msg);
416  filter_status_pub.publish(filter_status_msg);
417  }
418  }
419  }
420 
421 }
422 
union system_state_packet_t::@1 filter_status
void publish(const boost::shared_ptr< M > &message) const
an_packet_t * an_packet_decode(an_decoder_t *an_decoder)
#define an_decoder_increment(an_decoder, bytes_received)
int decode_system_state_packet(system_state_packet_t *system_state_packet, an_packet_t *an_packet)
int OpenComport(char *comport, int baudrate)
Definition: rs232.c:211
ROSCPP_DECL void init(int &argc, char **argv, const std::string &name, uint32_t options=0)
int PollComport(unsigned char *buf, int size)
Definition: rs232.c:311
void an_decoder_initialise(an_decoder_t *an_decoder)
int decode_quaternion_orientation_standard_deviation_packet(quaternion_orientation_standard_deviation_packet_t *quaternion_orientation_standard_deviation_packet, an_packet_t *an_packet)
struct system_state_packet_t::@0::@2 b
bool param(const std::string &param_name, T &param_val, const T &default_val) const
ROSCPP_DECL bool ok()
#define an_decoder_size(an_decoder)
Publisher advertise(const std::string &topic, uint32_t queue_size, bool latch=false)
void an_packet_free(an_packet_t **an_packet)
int main(int argc, char *argv[])
Definition: an_driver.cpp:48
#define RADIANS_TO_DEGREES
Definition: an_driver.cpp:46
ROSCPP_DECL void spinOnce()
#define an_decoder_pointer(an_decoder)
union system_state_packet_t::@0 system_status


advanced_navigation_driver
Author(s):
autogenerated on Thu Jun 6 2019 19:13:08