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> 46 #define RADIANS_TO_DEGREES (180.0/M_PI) 48 int main(
int argc,
char *argv[]) {
54 printf(
"\nYour Advanced Navigation ROS driver is currently running\nPress Ctrl-C to interrupt\n");
59 std::string imu_frame_id;
60 std::string nav_sat_frame_id;
61 std::string topic_prefix;
64 com_port = std::string(argv[1]);
65 baud_rate = atoi(argv[2]);
68 pnh.
param(
"port", com_port, std::string(
"/dev/ttyUSB0"));
69 pnh.
param(
"baud_rate", baud_rate, 115200);
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"));
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);
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;
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;
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;
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};
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};
122 diagnostic_msgs::DiagnosticStatus system_status_msg;
123 system_status_msg.level = 0;
124 system_status_msg.name =
"System Status";
125 system_status_msg.message =
"";
127 diagnostic_msgs::DiagnosticStatus filter_status_msg;
128 filter_status_msg.level = 0;
129 filter_status_msg.name =
"Filter Status";
130 filter_status_msg.message =
"";
139 if (
OpenComport(const_cast<char*>(com_port.c_str()), baud_rate))
141 printf(
"Could not open serial port: %s \n",com_port.c_str());
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;
171 nav_sat_fix_msg.status.status=0;
173 else if ((system_state_packet.
filter_status.
b.gnss_fix_type == 3) ||
176 nav_sat_fix_msg.status.status=1;
178 else if ((system_state_packet.
filter_status.
b.gnss_fix_type == 4) ||
182 nav_sat_fix_msg.status.status=2;
186 nav_sat_fix_msg.status.status=-1;
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,
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];
205 imu_msg.header.stamp.nsec=system_state_packet.
microseconds*1000;
206 imu_msg.header.frame_id=imu_frame_id;
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;
230 system_status_msg.message =
"";
231 system_status_msg.level = 0;
233 system_status_msg.level = 2;
234 system_status_msg.message = system_status_msg.message +
"0. System Failure! ";
236 if (system_state_packet.
system_status.
b.accelerometer_sensor_failure) {
237 system_status_msg.level = 2;
238 system_status_msg.message = system_status_msg.message +
"1. Accelerometer Sensor Failure! ";
240 if (system_state_packet.
system_status.
b.gyroscope_sensor_failure) {
241 system_status_msg.level = 2;
242 system_status_msg.message = system_status_msg.message +
"2. Gyroscope Sensor Failure! ";
244 if (system_state_packet.
system_status.
b.magnetometer_sensor_failure) {
245 system_status_msg.level = 2;
246 system_status_msg.message = system_status_msg.message +
"3. Magnetometer Sensor Failure! ";
248 if (system_state_packet.
system_status.
b.pressure_sensor_failure) {
249 system_status_msg.level = 2;
250 system_status_msg.message = system_status_msg.message +
"4. Pressure Sensor Failure! ";
253 system_status_msg.level = 2;
254 system_status_msg.message = system_status_msg.message +
"5. GNSS Failure! ";
256 if (system_state_packet.
system_status.
b.accelerometer_over_range) {
257 system_status_msg.level = 2;
258 system_status_msg.message = system_status_msg.message +
"6. Accelerometer Over Range! ";
261 system_status_msg.level = 2;
262 system_status_msg.message = system_status_msg.message +
"7. Gyroscope Over Range! ";
264 if (system_state_packet.
system_status.
b.magnetometer_over_range) {
265 system_status_msg.level = 2;
266 system_status_msg.message = system_status_msg.message +
"8. Magnetometer Over Range! ";
269 system_status_msg.level = 2;
270 system_status_msg.message = system_status_msg.message +
"9. Pressure Over Range! ";
272 if (system_state_packet.
system_status.
b.minimum_temperature_alarm) {
273 system_status_msg.level = 2;
274 system_status_msg.message = system_status_msg.message +
"10. Minimum Temperature Alarm! ";
276 if (system_state_packet.
system_status.
b.maximum_temperature_alarm) {
277 system_status_msg.level = 2;
278 system_status_msg.message = system_status_msg.message +
"11. Maximum Temperature Alarm! ";
281 system_status_msg.level = 2;
282 system_status_msg.message = system_status_msg.message +
"12. Low Voltage Alarm! ";
285 system_status_msg.level = 2;
286 system_status_msg.message = system_status_msg.message +
"13. High Voltage Alarm! ";
288 if (system_state_packet.
system_status.
b.gnss_antenna_disconnected) {
289 system_status_msg.level = 2;
290 system_status_msg.message = system_status_msg.message +
"14. GNSS Antenna Disconnected! ";
292 if (system_state_packet.
system_status.
b.serial_port_overflow_alarm) {
293 system_status_msg.level = 2;
294 system_status_msg.message = system_status_msg.message +
"15. Data Output Overflow Alarm! ";
298 filter_status_msg.message =
"";
299 filter_status_msg.level = 0;
300 if (system_state_packet.
filter_status.
b.orientation_filter_initialised) {
301 filter_status_msg.message = filter_status_msg.message +
"0. Orientation Filter Initialised. ";
304 filter_status_msg.level = 1;
305 filter_status_msg.message = filter_status_msg.message +
"0. Orientation Filter NOT Initialised. ";
308 filter_status_msg.message = filter_status_msg.message +
"1. Navigation Filter Initialised. ";
311 filter_status_msg.level = 1;
312 filter_status_msg.message = filter_status_msg.message +
"1. Navigation Filter NOT Initialised. ";
315 filter_status_msg.message = filter_status_msg.message +
"2. Heading Initialised. ";
318 filter_status_msg.level = 1;
319 filter_status_msg.message = filter_status_msg.message +
"2. Heading NOT Initialised. ";
322 filter_status_msg.message = filter_status_msg.message +
"3. UTC Time Initialised. ";
325 filter_status_msg.level = 1;
326 filter_status_msg.message = filter_status_msg.message +
"3. UTC Time NOT Initialised. ";
329 filter_status_msg.level = 1;
330 filter_status_msg.message = filter_status_msg.message +
"7. Event 1 Occured. ";
333 filter_status_msg.message = filter_status_msg.message +
"7. Event 1 NOT Occured. ";
336 filter_status_msg.level = 1;
337 filter_status_msg.message = filter_status_msg.message +
"8. Event 2 Occured. ";
340 filter_status_msg.message = filter_status_msg.message +
"8. Event 2 NOT Occured. ";
343 filter_status_msg.message = filter_status_msg.message +
"9. Internal GNSS Enabled. ";
346 filter_status_msg.level = 1;
347 filter_status_msg.message = filter_status_msg.message +
"9. Internal GNSS NOT Enabled. ";
349 if (system_state_packet.
filter_status.
b.magnetic_heading_enabled) {
350 filter_status_msg.message = filter_status_msg.message +
"10. Magnetic Heading Active. ";
353 filter_status_msg.level = 1;
354 filter_status_msg.message = filter_status_msg.message +
"10. Magnetic Heading NOT Active. ";
356 if (system_state_packet.
filter_status.
b.velocity_heading_enabled) {
357 filter_status_msg.message = filter_status_msg.message +
"11. Velocity Heading Enabled. ";
360 filter_status_msg.level = 1;
361 filter_status_msg.message = filter_status_msg.message +
"11. Velocity Heading NOT Enabled. ";
363 if (system_state_packet.
filter_status.
b.atmospheric_altitude_enabled) {
364 filter_status_msg.message = filter_status_msg.message +
"12. Atmospheric Altitude Enabled. ";
367 filter_status_msg.message = filter_status_msg.message +
"12. Atmospheric Altitude NOT Enabled. ";
368 filter_status_msg.level = 1;
370 if (system_state_packet.
filter_status.
b.external_position_active) {
371 filter_status_msg.message = filter_status_msg.message +
"13. External Position Active. ";
374 filter_status_msg.level = 1;
375 filter_status_msg.message = filter_status_msg.message +
"13. External Position NOT Active. ";
377 if (system_state_packet.
filter_status.
b.external_velocity_active) {
378 filter_status_msg.message = filter_status_msg.message +
"14. External Velocity Active. ";
381 filter_status_msg.level = 1;
382 filter_status_msg.message = filter_status_msg.message +
"14. External Velocity NOT Active. ";
384 if (system_state_packet.
filter_status.
b.external_heading_active) {
385 filter_status_msg.message = filter_status_msg.message +
"15. External Heading Active. ";
388 filter_status_msg.level = 1;
389 filter_status_msg.message = filter_status_msg.message +
"15. External Heading NOT Active. ";
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];
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);
float angular_velocity[3]
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)
float standard_deviation[3]
int decode_system_state_packet(system_state_packet_t *system_state_packet, an_packet_t *an_packet)
int OpenComport(char *comport, int baudrate)
ROSCPP_DECL void init(int &argc, char **argv, const std::string &name, uint32_t options=0)
int PollComport(unsigned char *buf, int size)
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)
float standard_deviation[4]
uint32_t unix_time_seconds
struct system_state_packet_t::@0::@2 b
bool param(const std::string ¶m_name, T ¶m_val, const T &default_val) const
#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[])
#define RADIANS_TO_DEGREES
float body_acceleration[3]
ROSCPP_DECL void spinOnce()
#define an_decoder_pointer(an_decoder)
union system_state_packet_t::@0 system_status