pacmod_node.cpp
Go to the documentation of this file.
1 /*
2 * Unpublished Copyright (c) 2009-2017 AutonomouStuff, LLC, All Rights Reserved.
3 *
4 * This file is part of the PACMod ROS 1.0 driver which is released under the MIT license.
5 * See file LICENSE included with this software or go to https://opensource.org/licenses/MIT for full license details.
6 */
7 
9 #include <thread>
10 #include <unistd.h>
11 #include <time.h>
12 #include <algorithm>
13 #include <unordered_map>
14 
15 #include <std_msgs/Int16.h>
16 #include <std_msgs/Bool.h>
17 #include <std_msgs/Float64.h>
18 #include <can_msgs/Frame.h>
19 
20 using namespace AS::Drivers::PACMod;
21 
23 const double watchdog_timeout = 0.3;
24 std::string veh_type_string = "POLARIS_GEM";
26 std::unordered_map<int64_t, ros::Publisher> pub_tx_list;
28 
29 // Vehicle-Specific Publishers
50 
51 // Vehicle-Specific Subscribers
52 std::shared_ptr<ros::Subscriber> wiper_set_cmd_sub,
55 
56 // Advertise published messages
68 
69 std::unordered_map<int64_t, std::shared_ptr<LockedData>> rx_list;
70 std::unordered_map<int64_t, int64_t> rpt_cmd_list;
71 
72 bool enable_state = false;
73 std::mutex enable_mut;
74 bool override_state = false;
75 std::mutex override_mut;
76 bool global_keep_going = true;
77 std::mutex keep_going_mut;
78 
79 /*
80 pacmod_msgs::PacmodCmd global_cmd_msg;
81 pacmod_msgs::PacmodCmd::ConstPtr global_cmd_msg_cpr(&global_cmd_msg);
82 */
83 std::chrono::milliseconds can_error_pause = std::chrono::milliseconds(1000);
84 
85 // Sets the PACMod enable flag through CAN.
86 void set_enable(bool val)
87 {
88  std::lock_guard<std::mutex> lck(enable_mut);
89  enable_state = val;
90 }
91 
92 // Listens for incoming requests to enable the PACMod
93 void callback_pacmod_enable(const std_msgs::Bool::ConstPtr& msg)
94 {
95  set_enable(msg->data);
96 }
97 
98 // Listens for incoming requests to change the state of the turn signals
99 void callback_turn_signal_set_cmd(const pacmod_msgs::PacmodCmd::ConstPtr& msg)
100 {
101  int64_t can_id = TurnSignalCmdMsg::CAN_ID;
102  auto rx_it = rx_list.find(can_id);
103 
104  if (rx_it != rx_list.end())
105  {
106  rx_it->second->setData(PacmodRxRosMsgHandler::unpackAndEncode(can_id, msg));
107  rx_it->second->setIsValid(true);
108  }
109  else
110  {
111  ROS_WARN("Received command message for ID 0x%lx for which we did not have an encoder.", can_id);
112  }
113 }
114 
115 // Listens for incoming requests to change the state of the headlights
116 void callback_headlight_set_cmd(const pacmod_msgs::PacmodCmd::ConstPtr& msg)
117 {
118  int64_t can_id = HeadlightCmdMsg::CAN_ID;
119  auto rx_it = rx_list.find(can_id);
120 
121  if (rx_it != rx_list.end())
122  {
123  rx_it->second->setData(PacmodRxRosMsgHandler::unpackAndEncode(can_id, msg));
124  rx_it->second->setIsValid(true);
125  }
126  else
127  {
128  ROS_WARN("Received command message for ID 0x%lx for which we did not have an encoder.", can_id);
129  }
130 }
131 
132 // Listens for incoming requests to change the state of the horn
133 void callback_horn_set_cmd(const pacmod_msgs::PacmodCmd::ConstPtr& msg)
134 {
135  int64_t can_id = HornCmdMsg::CAN_ID;
136  auto rx_it = rx_list.find(can_id);
137 
138  if (rx_it != rx_list.end())
139  {
140  rx_it->second->setData(PacmodRxRosMsgHandler::unpackAndEncode(can_id, msg));
141  rx_it->second->setIsValid(true);
142  }
143  else
144  {
145  ROS_WARN("Received command message for ID 0x%lx for which we did not have an encoder.", can_id);
146  }
147 }
148 
149 // Listens for incoming requests to change the state of the windshield wipers
150 void callback_wiper_set_cmd(const pacmod_msgs::PacmodCmd::ConstPtr& msg)
151 {
152  int64_t can_id = WiperCmdMsg::CAN_ID;
153  auto rx_it = rx_list.find(can_id);
154 
155  if (rx_it != rx_list.end())
156  {
157  rx_it->second->setData(PacmodRxRosMsgHandler::unpackAndEncode(can_id, msg));
158  rx_it->second->setIsValid(true);
159  }
160  else
161  {
162  ROS_WARN("Received command message for ID 0x%lx for which we did not have an encoder.", can_id);
163  }
164 }
165 
166 // Listens for incoming requests to change the gear shifter state
167 void callback_shift_set_cmd(const pacmod_msgs::PacmodCmd::ConstPtr& msg)
168 {
169  int64_t can_id = ShiftCmdMsg::CAN_ID;
170  auto rx_it = rx_list.find(can_id);
171 
172  if (rx_it != rx_list.end())
173  {
174  rx_it->second->setData(PacmodRxRosMsgHandler::unpackAndEncode(can_id, msg));
175  rx_it->second->setIsValid(true);
176  }
177  else
178  {
179  ROS_WARN("Received command message for ID 0x%lx for which we did not have an encoder.", can_id);
180  }
181 }
182 
183 // Listens for incoming requests to change the position of the throttle pedal
184 void callback_accelerator_set_cmd(const pacmod_msgs::PacmodCmd::ConstPtr& msg)
185 {
186  int64_t can_id = AccelCmdMsg::CAN_ID;
187  auto rx_it = rx_list.find(can_id);
188 
189  if (rx_it != rx_list.end())
190  {
191  rx_it->second->setData(PacmodRxRosMsgHandler::unpackAndEncode(can_id, msg));
192  rx_it->second->setIsValid(true);
193  }
194  else
195  {
196  ROS_WARN("Received command message for ID 0x%lx for which we did not have an encoder.", can_id);
197  }
198 }
199 
200 // Listens for incoming requests to change the position of the steering wheel with a speed limit
201 void callback_steering_set_cmd(const pacmod_msgs::PositionWithSpeed::ConstPtr& msg)
202 {
203  int64_t can_id = SteerCmdMsg::CAN_ID;
204  auto rx_it = rx_list.find(can_id);
205 
206  if (rx_it != rx_list.end())
207  {
208  rx_it->second->setData(PacmodRxRosMsgHandler::unpackAndEncode(can_id, msg));
209  rx_it->second->setIsValid(true);
210  }
211  else
212  {
213  ROS_WARN("Received command message for ID 0x%lx for which we did not have an encoder.", can_id);
214  }
215 }
216 
217 // Listens for incoming requests to change the position of the brake pedal
218 void callback_brake_set_cmd(const pacmod_msgs::PacmodCmd::ConstPtr& msg)
219 {
220  int64_t can_id = BrakeCmdMsg::CAN_ID;
221  auto rx_it = rx_list.find(can_id);
222 
223  if (rx_it != rx_list.end())
224  {
225  rx_it->second->setData(PacmodRxRosMsgHandler::unpackAndEncode(can_id, msg));
226  rx_it->second->setIsValid(true);
227  }
228  else
229  {
230  ROS_WARN("Received command message for ID 0x%lx for which we did not have an encoder.", can_id);
231  }
232 }
233 
234 void send_can(int32_t id, const std::vector<unsigned char>& vec)
235 {
236  can_msgs::Frame frame;
237  frame.id = id;
238  frame.is_rtr = false;
239  frame.is_extended = false;
240  frame.is_error = false;
241  frame.dlc = 8;
242  std::copy(vec.begin(), vec.end(), frame.data.begin());
243 
244  frame.header.stamp = ros::Time::now();
245 
246  can_rx_pub.publish(frame);
247 }
248 
249 void can_write()
250 {
251  std::vector<unsigned char> data;
252 
253  const std::chrono::milliseconds loop_pause = std::chrono::milliseconds(33);
254  const std::chrono::milliseconds inter_msg_pause = std::chrono::milliseconds(1);
255  bool keep_going = true;
256 
257  // Set local to global value before looping.
258  keep_going_mut.lock();
259  keep_going = global_keep_going;
260  keep_going_mut.unlock();
261 
262  while (keep_going)
263  {
264  /*
265  // Create Global Command
266  enable_mut.lock();
267  global_cmd_msg.enable = enable_state;
268  enable_mut.unlock();
269 
270  global_cmd_msg.clear = true;
271  global_cmd_msg.ignore = false;
272 
273  auto rx_it = rx_list.find(GlobalCmdMsg::CAN_ID);
274  rx_it->second->setData(PacmodRxRosMsgHandler::unpackAndEncode(GlobalCmdMsg::CAN_ID, global_cmd_msg_cpr));
275  rx_it->second->setIsValid(true);
276  */
277 
278  // Temporarily write the Global message separately.
279  GlobalCmdMsg global_obj;
280  bool local_enable;
281 
282  enable_mut.lock();
283  local_enable = enable_state;
284  enable_mut.unlock();
285 
286  global_obj.encode(local_enable, true, false);
287 
288  // ret = can_writer.write(GlobalCmdMsg::CAN_ID, &global_obj.data[0], 8, true);
289  send_can(GlobalCmdMsg::CAN_ID, global_obj.data);
290 
291  std::this_thread::sleep_for(inter_msg_pause);
292 
293  if (local_enable)
294  {
295  // Write all the data that we have received.
296  for (const auto& element : rx_list)
297  {
298  // Make sure the data are valid.
299  if (element.second->isValid())
300  {
301  send_can(element.first, element.second->getData());
302  std::this_thread::sleep_for(inter_msg_pause);
303  }
304  }
305  }
306 
307  std::chrono::system_clock::time_point next_time = std::chrono::system_clock::now();
308  next_time += loop_pause;
309  std::this_thread::sleep_until(next_time);
310 
311  // Set local to global immediately before next loop.
312  keep_going_mut.lock();
313  keep_going = global_keep_going;
314  keep_going_mut.unlock();
315  }
316 }
317 
318 void can_read(const can_msgs::Frame::ConstPtr &msg)
319 {
320  std_msgs::Bool bool_pub_msg;
321  auto parser_class = PacmodTxMsg::make_message(msg->id);
322  auto pub = pub_tx_list.find(msg->id);
323 
324  // Only parse messages for which we have a parser and a publisher.
325  if (parser_class != NULL && pub != pub_tx_list.end())
326  {
327  parser_class->parse(const_cast<unsigned char *>(&msg->data[0]));
328  handler.fillAndPublish(msg->id, "pacmod", pub->second, parser_class);
329 
330  bool local_enable = false;
331 
332  enable_mut.lock();
333  local_enable = enable_state;
334  enable_mut.unlock();
335 
336  if (!local_enable)
337  {
338  // If we're disabled, set all of the system commands
339  // to be the current report values. This ensures that
340  // when we enable, we are in the same state as the vehicle.
341 
342  // Find the cmd value for this rpt.
343  auto cmd = rpt_cmd_list.find(msg->id);
344 
345  if (cmd != rpt_cmd_list.end())
346  {
347  // Find the data we need to set.
348  auto rx_it = rx_list.find(cmd->second);
349 
350  if (rx_it != rx_list.end())
351  {
352  if (msg->id == TurnSignalRptMsg::CAN_ID)
353  {
354  auto dc_parser = std::dynamic_pointer_cast<TurnSignalRptMsg>(parser_class);
355  TurnSignalCmdMsg encoder;
356 
357  encoder.encode(dc_parser->output);
358  rx_it->second->setData(encoder.data);
359  }
360  else if (msg->id == ShiftRptMsg::CAN_ID)
361  {
362  auto dc_parser = std::dynamic_pointer_cast<ShiftRptMsg>(parser_class);
363  ShiftCmdMsg encoder;
364 
365  encoder.encode(dc_parser->output);
366  rx_it->second->setData(encoder.data);
367  }
368  else if (msg->id == AccelRptMsg::CAN_ID)
369  {
370  auto dc_parser = std::dynamic_pointer_cast<AccelRptMsg>(parser_class);
371  AccelCmdMsg encoder;
372 
373  encoder.encode(dc_parser->output);
374  rx_it->second->setData(encoder.data);
375  }
376  else if (msg->id == SteerRptMsg::CAN_ID)
377  {
378  auto dc_parser = std::dynamic_pointer_cast<SteerRptMsg>(parser_class);
379  SteerCmdMsg encoder;
380 
381  encoder.encode(dc_parser->output, 2.0);
382  rx_it->second->setData(encoder.data);
383  }
384  else if (msg->id == BrakeRptMsg::CAN_ID)
385  {
386  auto dc_parser = std::dynamic_pointer_cast<BrakeRptMsg>(parser_class);
387  BrakeCmdMsg encoder;
388 
389  encoder.encode(dc_parser->output);
390  rx_it->second->setData(encoder.data);
391  }
392  else if (msg->id == WiperRptMsg::CAN_ID)
393  {
394  auto dc_parser = std::dynamic_pointer_cast<WiperRptMsg>(parser_class);
395  WiperCmdMsg encoder;
396 
397  encoder.encode(dc_parser->output);
398  rx_it->second->setData(encoder.data);
399  }
400  else if (msg->id == HornRptMsg::CAN_ID)
401  {
402  auto dc_parser = std::dynamic_pointer_cast<HornRptMsg>(parser_class);
403  HornCmdMsg encoder;
404 
405  encoder.encode(dc_parser->output);
406  rx_it->second->setData(encoder.data);
407  }
408 
409  rx_it->second->setIsValid(true);
410  }
411  }
412  }
413 
414  if (msg->id == GlobalRptMsg::CAN_ID)
415  {
416  auto dc_parser = std::dynamic_pointer_cast<GlobalRptMsg>(parser_class);
417 
418  bool_pub_msg.data = (dc_parser->enabled);
419  enable_pub.publish(bool_pub_msg);
420 
421  if (dc_parser->override_active)
422  {
423  set_enable(false);
424  }
425  }
426  else if (msg->id == VehicleSpeedRptMsg::CAN_ID)
427  {
428  auto dc_parser = std::dynamic_pointer_cast<VehicleSpeedRptMsg>(parser_class);
429 
430  // Now publish in m/s
431  std_msgs::Float64 veh_spd_ms_msg;
432  veh_spd_ms_msg.data = (dc_parser->vehicle_speed) * 0.44704;
433  vehicle_speed_ms_pub.publish(veh_spd_ms_msg);
434  }
435  }
436 }
437 
438 int main(int argc, char *argv[])
439 {
440  ros::init(argc, argv, "pacmod");
441  ros::AsyncSpinner spinner(2);
442  ros::NodeHandle n;
443  ros::NodeHandle priv("~");
444  ros::Rate loop_rate(1.0); // PACMod is sending at ~30Hz.
445 
446  // Wait for time to be valid
447  while (ros::Time::now().nsec == 0) {}
448 
449  // Get and validate parameters
450  if (priv.getParam("vehicle_type", veh_type_string))
451  {
452  ROS_INFO("PACMod - Got vehicle type of: %s", veh_type_string.c_str());
453 
454  if (veh_type_string == "POLARIS_GEM")
455  {
457  }
458  else if (veh_type_string == "POLARIS_RANGER")
459  {
461  }
462  else if (veh_type_string == "INTERNATIONAL_PROSTAR_122")
463  {
465  }
466  else if (veh_type_string == "LEXUS_RX_450H")
467  {
469  }
470  else
471  {
473  ROS_WARN("PACMod - An invalid vehicle type was entered. Assuming POLARIS_GEM.");
474  }
475  }
476 
477  // Advertise published messages
478  can_rx_pub = n.advertise<can_msgs::Frame>("can_rx", 20);
479  global_rpt_pub = n.advertise<pacmod_msgs::GlobalRpt>("parsed_tx/global_rpt", 20);
480  vin_rpt_pub = n.advertise<pacmod_msgs::VinRpt>("parsed_tx/vin_rpt", 5);
481  turn_rpt_pub = n.advertise<pacmod_msgs::SystemRptInt>("parsed_tx/turn_rpt", 20);
482  shift_rpt_pub = n.advertise<pacmod_msgs::SystemRptInt>("parsed_tx/shift_rpt", 20);
483  accel_rpt_pub = n.advertise<pacmod_msgs::SystemRptFloat>("parsed_tx/accel_rpt", 20);
484  steer_rpt_pub = n.advertise<pacmod_msgs::SystemRptFloat>("parsed_tx/steer_rpt", 20);
485  brake_rpt_pub = n.advertise<pacmod_msgs::SystemRptFloat>("parsed_tx/brake_rpt", 20);
486  vehicle_speed_pub = n.advertise<pacmod_msgs::VehicleSpeedRpt>("parsed_tx/vehicle_speed_rpt", 20);
487  vehicle_speed_ms_pub = n.advertise<std_msgs::Float64>("as_tx/vehicle_speed", 20);
488  enable_pub = n.advertise<std_msgs::Bool>("as_tx/enable", 20, true);
489 
490  std::string frame_id = "pacmod";
491 
492  // Populate handler list
493  pub_tx_list.insert(std::make_pair(GlobalRptMsg::CAN_ID, global_rpt_pub));
494  pub_tx_list.insert(std::make_pair(VinRptMsg::CAN_ID, vin_rpt_pub));
495  pub_tx_list.insert(std::make_pair(TurnSignalRptMsg::CAN_ID, turn_rpt_pub));
496  pub_tx_list.insert(std::make_pair(ShiftRptMsg::CAN_ID, shift_rpt_pub));
497  pub_tx_list.insert(std::make_pair(AccelRptMsg::CAN_ID, accel_rpt_pub));
498  pub_tx_list.insert(std::make_pair(SteerRptMsg::CAN_ID, steer_rpt_pub));
499  pub_tx_list.insert(std::make_pair(BrakeRptMsg::CAN_ID, brake_rpt_pub));
500  pub_tx_list.insert(std::make_pair(VehicleSpeedRptMsg::CAN_ID, vehicle_speed_pub));
501 
502  // Subscribe to messages
503  ros::Subscriber can_tx_sub = n.subscribe("can_tx", 20, can_read);
504  ros::Subscriber turn_set_cmd_sub = n.subscribe("as_rx/turn_cmd", 20, callback_turn_signal_set_cmd);
505  ros::Subscriber shift_set_cmd_sub = n.subscribe("as_rx/shift_cmd", 20, callback_shift_set_cmd);
506  ros::Subscriber accelerator_set_cmd = n.subscribe("as_rx/accel_cmd", 20, callback_accelerator_set_cmd);
507  ros::Subscriber steering_set_cmd = n.subscribe("as_rx/steer_cmd", 20, callback_steering_set_cmd);
508  ros::Subscriber brake_set_cmd = n.subscribe("as_rx/brake_cmd", 20, callback_brake_set_cmd);
509  ros::Subscriber enable_sub = n.subscribe("as_rx/enable", 20, callback_pacmod_enable);
510 
511  // Populate rx list
512  std::shared_ptr<LockedData> global_data(new LockedData);
513  std::shared_ptr<LockedData> turn_data(new LockedData);
514  std::shared_ptr<LockedData> shift_data(new LockedData);
515  std::shared_ptr<LockedData> accel_data(new LockedData);
516  std::shared_ptr<LockedData> steer_data(new LockedData);
517  std::shared_ptr<LockedData> brake_data(new LockedData);
518 
519  rx_list.insert(std::make_pair(GlobalCmdMsg::CAN_ID, global_data));
520  rx_list.insert(std::make_pair(TurnSignalCmdMsg::CAN_ID, turn_data));
521  rx_list.insert(std::make_pair(ShiftCmdMsg::CAN_ID, shift_data));
522  rx_list.insert(std::make_pair(AccelCmdMsg::CAN_ID, accel_data));
523  rx_list.insert(std::make_pair(SteerCmdMsg::CAN_ID, steer_data));
524  rx_list.insert(std::make_pair(BrakeCmdMsg::CAN_ID, brake_data));
525 
529  {
530  brake_rpt_detail_1_pub = n.advertise<pacmod_msgs::MotorRpt1>("parsed_tx/brake_rpt_detail_1", 20);
531  brake_rpt_detail_2_pub = n.advertise<pacmod_msgs::MotorRpt2>("parsed_tx/brake_rpt_detail_2", 20);
532  brake_rpt_detail_3_pub = n.advertise<pacmod_msgs::MotorRpt3>("parsed_tx/brake_rpt_detail_3", 20);
533  steering_rpt_detail_1_pub = n.advertise<pacmod_msgs::MotorRpt1>("parsed_tx/steer_rpt_detail_1", 20);
534  steering_rpt_detail_2_pub = n.advertise<pacmod_msgs::MotorRpt2>("parsed_tx/steer_rpt_detail_2", 20);
535  steering_rpt_detail_3_pub = n.advertise<pacmod_msgs::MotorRpt3>("parsed_tx/steer_rpt_detail_3", 20);
536 
537  pub_tx_list.insert(std::make_pair(BrakeMotorRpt1Msg::CAN_ID, brake_rpt_detail_1_pub));
538  pub_tx_list.insert(std::make_pair(BrakeMotorRpt2Msg::CAN_ID, brake_rpt_detail_2_pub));
539  pub_tx_list.insert(std::make_pair(BrakeMotorRpt3Msg::CAN_ID, brake_rpt_detail_3_pub));
540  pub_tx_list.insert(std::make_pair(SteerMotorRpt1Msg::CAN_ID, steering_rpt_detail_1_pub));
541  pub_tx_list.insert(std::make_pair(SteerMotorRpt2Msg::CAN_ID, steering_rpt_detail_2_pub));
542  pub_tx_list.insert(std::make_pair(SteerMotorRpt3Msg::CAN_ID, steering_rpt_detail_3_pub));
543  }
544 
546  {
547  wiper_rpt_pub = n.advertise<pacmod_msgs::SystemRptInt>("parsed_tx/wiper_rpt", 20);
548 
549  pub_tx_list.insert(std::make_pair(WiperRptMsg::CAN_ID, wiper_rpt_pub));
550 
551  wiper_set_cmd_sub = std::shared_ptr<ros::Subscriber>(new ros::Subscriber(n.subscribe("as_rx/wiper_cmd",
552  20,
554 
555  std::shared_ptr<LockedData> wiper_data(new LockedData);
556  rx_list.insert(std::make_pair(WiperCmdMsg::CAN_ID, wiper_data));
557  }
558 
560  {
561  horn_rpt_pub = n.advertise<pacmod_msgs::SystemRptInt>("parsed_tx/horn_rpt", 20);
562  steer_rpt_2_pub = n.advertise<pacmod_msgs::SystemRptFloat>("parsed_tx/steer_rpt_2", 20);
563  steer_rpt_3_pub = n.advertise<pacmod_msgs::SystemRptFloat>("parsed_tx/steer_rpt_3", 20);
564  wheel_speed_rpt_pub = n.advertise<pacmod_msgs::WheelSpeedRpt>("parsed_tx/wheel_speed_rpt", 20);
565  steering_pid_rpt_1_pub = n.advertise<pacmod_msgs::SteeringPIDRpt1>("parsed_tx/steer_pid_rpt_1", 20);
566  steering_pid_rpt_2_pub = n.advertise<pacmod_msgs::SteeringPIDRpt2>("parsed_tx/steer_pid_rpt_2", 20);
567  steering_pid_rpt_3_pub = n.advertise<pacmod_msgs::SteeringPIDRpt3>("parsed_tx/steer_pid_rpt_3", 20);
568  steering_pid_rpt_4_pub = n.advertise<pacmod_msgs::SteeringPIDRpt4>("parsed_tx/steer_pid_rpt_4", 20);
569  yaw_rate_rpt_pub = n.advertise<pacmod_msgs::YawRateRpt>("parsed_tx/yaw_rate_rpt", 20);
570  lat_lon_heading_rpt_pub = n.advertise<pacmod_msgs::LatLonHeadingRpt>("parsed_tx/lat_lon_heading_rpt", 20);
571  date_time_rpt_pub = n.advertise<pacmod_msgs::DateTimeRpt>("parsed_tx/date_time_rpt", 20);
572 
573  pub_tx_list.insert(std::make_pair(HornRptMsg::CAN_ID, horn_rpt_pub));
574  pub_tx_list.insert(std::make_pair(SteerRpt2Msg::CAN_ID, steer_rpt_2_pub));
575  pub_tx_list.insert(std::make_pair(SteerRpt3Msg::CAN_ID, steer_rpt_3_pub));
576  pub_tx_list.insert(std::make_pair(WheelSpeedRptMsg::CAN_ID, wheel_speed_rpt_pub));
577  pub_tx_list.insert(std::make_pair(SteeringPIDRpt1Msg::CAN_ID, steering_pid_rpt_1_pub));
578  pub_tx_list.insert(std::make_pair(SteeringPIDRpt2Msg::CAN_ID, steering_pid_rpt_2_pub));
579  pub_tx_list.insert(std::make_pair(SteeringPIDRpt3Msg::CAN_ID, steering_pid_rpt_3_pub));
580  pub_tx_list.insert(std::make_pair(SteeringPIDRpt4Msg::CAN_ID, steering_pid_rpt_4_pub));
581  pub_tx_list.insert(std::make_pair(YawRateRptMsg::CAN_ID, yaw_rate_rpt_pub));
582  pub_tx_list.insert(std::make_pair(LatLonHeadingRptMsg::CAN_ID, lat_lon_heading_rpt_pub));
583  pub_tx_list.insert(std::make_pair(DateTimeRptMsg::CAN_ID, date_time_rpt_pub));
584 
586  std::shared_ptr<ros::Subscriber>(new ros::Subscriber(n.subscribe("as_rx/headlight_cmd",
587  20,
590  std::shared_ptr<ros::Subscriber>(new ros::Subscriber(n.subscribe("as_rx/horn_cmd",
591  20,
593 
594  std::shared_ptr<LockedData> headlight_data(new LockedData);
595  std::shared_ptr<LockedData> horn_data(new LockedData);
596 
597  rx_list.insert(std::make_pair(HeadlightCmdMsg::CAN_ID, headlight_data));
598  rx_list.insert(std::make_pair(HornCmdMsg::CAN_ID, horn_data));
599  }
600 
602  {
603  headlight_rpt_pub = n.advertise<pacmod_msgs::SystemRptInt>("parsed_tx/headlight_rpt", 20);
604  parking_brake_status_rpt_pub =
605  n.advertise<pacmod_msgs::ParkingBrakeStatusRpt>("parsed_tx/parking_brake_status_rpt", 20);
606 
607  pub_tx_list.insert(std::make_pair(HeadlightRptMsg::CAN_ID, headlight_rpt_pub));
608  pub_tx_list.insert(std::make_pair(ParkingBrakeStatusRptMsg::CAN_ID, parking_brake_status_rpt_pub));
609  }
610 
611  // Populate report/command list.
613  rpt_cmd_list.insert(std::make_pair(ShiftRptMsg::CAN_ID, ShiftCmdMsg::CAN_ID));
614  rpt_cmd_list.insert(std::make_pair(AccelRptMsg::CAN_ID, AccelCmdMsg::CAN_ID));
615  rpt_cmd_list.insert(std::make_pair(SteerRptMsg::CAN_ID, SteerCmdMsg::CAN_ID));
616  rpt_cmd_list.insert(std::make_pair(BrakeRptMsg::CAN_ID, BrakeCmdMsg::CAN_ID));
617 
619  {
620  rpt_cmd_list.insert(std::make_pair(WiperRptMsg::CAN_ID, WiperCmdMsg::CAN_ID));
621  }
623  {
624  rpt_cmd_list.insert(std::make_pair(HornRptMsg::CAN_ID, HornCmdMsg::CAN_ID));
625  }
626 
627  // Set initial state
628  set_enable(false);
629 
630  // Start CAN sending thread.
631  std::thread can_write_thread(can_write);
632  // Start callback spinner.
633  spinner.start();
634 
636 
637  // Make sure it's disabled when node shuts down
638  set_enable(false);
639 
640  keep_going_mut.lock();
641  global_keep_going = false;
642  keep_going_mut.unlock();
643 
644  can_write_thread.join();
645 
646  return 0;
647 }
648 
void set_enable(bool val)
Definition: pacmod_node.cpp:86
ros::Publisher steering_rpt_detail_2_pub
Definition: pacmod_node.cpp:45
ros::Publisher accel_rpt_pub
Definition: pacmod_node.cpp:61
static const int64_t CAN_ID
Definition: pacmod_core.h:455
void encode(uint8_t horn_cmd)
ros::Publisher headlight_rpt_pub
Definition: pacmod_node.cpp:31
void callback_pacmod_enable(const std_msgs::Bool::ConstPtr &msg)
Definition: pacmod_node.cpp:93
std::unordered_map< int64_t, std::shared_ptr< LockedData > > rx_list
Definition: pacmod_node.cpp:69
ros::Publisher vin_rpt_pub
Definition: pacmod_node.cpp:58
void can_read(const can_msgs::Frame::ConstPtr &msg)
ros::Publisher yaw_rate_rpt_pub
Definition: pacmod_node.cpp:43
bool global_keep_going
Definition: pacmod_node.cpp:76
void publish(const boost::shared_ptr< M > &message) const
const double watchdog_timeout
Definition: pacmod_node.cpp:23
ros::Publisher date_time_rpt_pub
Definition: pacmod_node.cpp:41
static const int64_t CAN_ID
Definition: pacmod_core.h:114
std::shared_ptr< ros::Subscriber > wiper_set_cmd_sub
Definition: pacmod_node.cpp:52
Subscriber subscribe(const std::string &topic, uint32_t queue_size, void(T::*fp)(M), T *obj, const TransportHints &transport_hints=TransportHints())
std::mutex enable_mut
Definition: pacmod_node.cpp:73
static std::vector< uint8_t > unpackAndEncode(const int64_t &can_id, const pacmod_msgs::PacmodCmd::ConstPtr &msg)
void callback_turn_signal_set_cmd(const pacmod_msgs::PacmodCmd::ConstPtr &msg)
Definition: pacmod_node.cpp:99
static const int64_t CAN_ID
Definition: pacmod_core.h:410
std::unordered_map< int64_t, int64_t > rpt_cmd_list
Definition: pacmod_node.cpp:70
ros::Publisher steer_rpt_pub
Definition: pacmod_node.cpp:62
static const int64_t CAN_ID
Definition: pacmod_core.h:437
ROSCPP_DECL void init(int &argc, char **argv, const std::string &name, uint32_t options=0)
ros::Publisher vehicle_speed_ms_pub
Definition: pacmod_node.cpp:65
double last_global_rpt_msg_received
Definition: pacmod_node.cpp:22
static const int64_t CAN_ID
Definition: pacmod_core.h:153
ros::Publisher steering_pid_rpt_2_pub
Definition: pacmod_node.cpp:37
ros::Publisher turn_rpt_pub
Definition: pacmod_node.cpp:59
ros::Publisher can_rx_pub
Definition: pacmod_node.cpp:67
void callback_wiper_set_cmd(const pacmod_msgs::PacmodCmd::ConstPtr &msg)
ros::Publisher steer_rpt_3_pub
Definition: pacmod_node.cpp:34
void encode(double steer_pos, double steer_spd)
ros::Publisher steering_pid_rpt_3_pub
Definition: pacmod_node.cpp:38
static const int64_t CAN_ID
Definition: pacmod_core.h:383
#define ROS_WARN(...)
static const int64_t CAN_ID
Definition: pacmod_core.h:107
ros::Publisher steering_rpt_detail_1_pub
Definition: pacmod_node.cpp:44
ros::Publisher steering_pid_rpt_1_pub
Definition: pacmod_node.cpp:36
static const int64_t CAN_ID
Definition: pacmod_core.h:60
static const int64_t CAN_ID
Definition: pacmod_core.h:146
void encode(double accel_cmd)
std::vector< uint8_t > data
Definition: pacmod_core.h:376
void encode(uint8_t wiper_cmd)
ros::Publisher brake_rpt_detail_3_pub
Definition: pacmod_node.cpp:49
int main(int argc, char *argv[])
ros::Publisher wiper_rpt_pub
Definition: pacmod_node.cpp:30
ros::Publisher shift_rpt_pub
Definition: pacmod_node.cpp:60
std::string veh_type_string
Definition: pacmod_node.cpp:24
void can_write()
void encode(double brake_cmd)
void encode(uint8_t turn_signal_cmd)
void encode(uint8_t shift_cmd)
static const int64_t CAN_ID
Definition: pacmod_core.h:419
static const int64_t CAN_ID
Definition: pacmod_core.h:100
ros::Publisher horn_rpt_pub
Definition: pacmod_node.cpp:32
ros::Publisher wheel_speed_rpt_pub
Definition: pacmod_node.cpp:35
static const int64_t CAN_ID
Definition: pacmod_core.h:428
void callback_brake_set_cmd(const pacmod_msgs::PacmodCmd::ConstPtr &msg)
#define ROS_INFO(...)
VehicleType veh_type
Definition: pacmod_node.cpp:25
void callback_shift_set_cmd(const pacmod_msgs::PacmodCmd::ConstPtr &msg)
ros::Publisher steering_pid_rpt_4_pub
Definition: pacmod_node.cpp:39
static const int64_t CAN_ID
Definition: pacmod_core.h:43
ros::Publisher steer_rpt_2_pub
Definition: pacmod_node.cpp:33
std::chrono::milliseconds can_error_pause
Definition: pacmod_node.cpp:83
ros::Publisher parking_brake_status_rpt_pub
Definition: pacmod_node.cpp:42
Publisher advertise(const std::string &topic, uint32_t queue_size, bool latch=false)
ros::Publisher brake_rpt_detail_1_pub
Definition: pacmod_node.cpp:47
void callback_horn_set_cmd(const pacmod_msgs::PacmodCmd::ConstPtr &msg)
ros::Publisher enable_pub
Definition: pacmod_node.cpp:66
static const int64_t CAN_ID
Definition: pacmod_core.h:132
std::mutex override_mut
Definition: pacmod_node.cpp:75
std::shared_ptr< ros::Subscriber > horn_set_cmd_sub
Definition: pacmod_node.cpp:52
PacmodTxRosMsgHandler handler
Definition: pacmod_node.cpp:27
ros::Publisher brake_rpt_detail_2_pub
Definition: pacmod_node.cpp:48
static const int64_t CAN_ID
Definition: pacmod_core.h:160
ros::Publisher vehicle_speed_pub
Definition: pacmod_node.cpp:64
ros::Publisher global_rpt_pub
Definition: pacmod_node.cpp:57
bool getParam(const std::string &key, std::string &s) const
static Time now()
static const int64_t CAN_ID
Definition: pacmod_core.h:139
ros::Publisher lat_lon_heading_rpt_pub
Definition: pacmod_node.cpp:40
ros::Publisher steering_rpt_detail_3_pub
Definition: pacmod_node.cpp:46
void send_can(int32_t id, const std::vector< unsigned char > &vec)
ros::Publisher brake_rpt_pub
Definition: pacmod_node.cpp:63
void fillAndPublish(const int64_t &can_id, std::string frame_id, const ros::Publisher &pub, const std::shared_ptr< PacmodTxMsg > &parser_class)
static std::shared_ptr< PacmodTxMsg > make_message(const int64_t &can_id)
Definition: pacmod_core.cpp:50
std::mutex keep_going_mut
Definition: pacmod_node.cpp:77
std::unordered_map< int64_t, ros::Publisher > pub_tx_list
Definition: pacmod_node.cpp:26
static const int64_t CAN_ID
Definition: pacmod_core.h:446
void callback_steering_set_cmd(const pacmod_msgs::PositionWithSpeed::ConstPtr &msg)
void encode(bool enable, bool clear_override, bool ignore_overide)
std::shared_ptr< ros::Subscriber > headlight_set_cmd_sub
Definition: pacmod_node.cpp:52
void callback_headlight_set_cmd(const pacmod_msgs::PacmodCmd::ConstPtr &msg)
ROSCPP_DECL void waitForShutdown()
void callback_accelerator_set_cmd(const pacmod_msgs::PacmodCmd::ConstPtr &msg)
bool override_state
Definition: pacmod_node.cpp:74
bool enable_state
Definition: pacmod_node.cpp:72


pacmod
Author(s): Joe Driscoll , Josh Whitley
autogenerated on Mon Jun 10 2019 14:08:17