00001
00002
00003
00004
00005
00006
00007
00008 #include <pacmod_ros_msg_handler.h>
00009 #include <thread>
00010 #include <unistd.h>
00011 #include <time.h>
00012 #include <algorithm>
00013 #include <unordered_map>
00014
00015 #include <std_msgs/Int16.h>
00016 #include <std_msgs/Bool.h>
00017 #include <std_msgs/Float64.h>
00018 #include <can_msgs/Frame.h>
00019
00020 using namespace AS::Drivers::PACMod;
00021
00022 double last_global_rpt_msg_received = 0.0;
00023 const double watchdog_timeout = 0.3;
00024 std::string veh_type_string = "POLARIS_GEM";
00025 VehicleType veh_type = VehicleType::POLARIS_GEM;
00026 std::unordered_map<int64_t, ros::Publisher> pub_tx_list;
00027 PacmodTxRosMsgHandler handler;
00028
00029
00030 ros::Publisher wiper_rpt_pub;
00031 ros::Publisher headlight_rpt_pub;
00032 ros::Publisher horn_rpt_pub;
00033 ros::Publisher steer_rpt_2_pub;
00034 ros::Publisher steer_rpt_3_pub;
00035 ros::Publisher wheel_speed_rpt_pub;
00036 ros::Publisher steering_pid_rpt_1_pub;
00037 ros::Publisher steering_pid_rpt_2_pub;
00038 ros::Publisher steering_pid_rpt_3_pub;
00039 ros::Publisher steering_pid_rpt_4_pub;
00040 ros::Publisher lat_lon_heading_rpt_pub;
00041 ros::Publisher date_time_rpt_pub;
00042 ros::Publisher parking_brake_status_rpt_pub;
00043 ros::Publisher yaw_rate_rpt_pub;
00044 ros::Publisher steering_rpt_detail_1_pub;
00045 ros::Publisher steering_rpt_detail_2_pub;
00046 ros::Publisher steering_rpt_detail_3_pub;
00047 ros::Publisher brake_rpt_detail_1_pub;
00048 ros::Publisher brake_rpt_detail_2_pub;
00049 ros::Publisher brake_rpt_detail_3_pub;
00050
00051
00052 std::shared_ptr<ros::Subscriber> wiper_set_cmd_sub,
00053 headlight_set_cmd_sub,
00054 horn_set_cmd_sub;
00055
00056
00057 ros::Publisher global_rpt_pub;
00058 ros::Publisher vin_rpt_pub;
00059 ros::Publisher turn_rpt_pub;
00060 ros::Publisher shift_rpt_pub;
00061 ros::Publisher accel_rpt_pub;
00062 ros::Publisher steer_rpt_pub;
00063 ros::Publisher brake_rpt_pub;
00064 ros::Publisher vehicle_speed_pub;
00065 ros::Publisher vehicle_speed_ms_pub;
00066 ros::Publisher enable_pub;
00067 ros::Publisher can_rx_pub;
00068
00069 std::unordered_map<int64_t, std::shared_ptr<LockedData>> rx_list;
00070 std::unordered_map<int64_t, int64_t> rpt_cmd_list;
00071
00072 bool enable_state = false;
00073 std::mutex enable_mut;
00074 bool override_state = false;
00075 std::mutex override_mut;
00076 bool global_keep_going = true;
00077 std::mutex keep_going_mut;
00078
00079
00080
00081
00082
00083 std::chrono::milliseconds can_error_pause = std::chrono::milliseconds(1000);
00084
00085
00086 void set_enable(bool val)
00087 {
00088 std::lock_guard<std::mutex> lck(enable_mut);
00089 enable_state = val;
00090 }
00091
00092
00093 void callback_pacmod_enable(const std_msgs::Bool::ConstPtr& msg)
00094 {
00095 set_enable(msg->data);
00096 }
00097
00098
00099 void callback_turn_signal_set_cmd(const pacmod_msgs::PacmodCmd::ConstPtr& msg)
00100 {
00101 int64_t can_id = TurnSignalCmdMsg::CAN_ID;
00102 auto rx_it = rx_list.find(can_id);
00103
00104 if (rx_it != rx_list.end())
00105 {
00106 rx_it->second->setData(PacmodRxRosMsgHandler::unpackAndEncode(can_id, msg));
00107 rx_it->second->setIsValid(true);
00108 }
00109 else
00110 {
00111 ROS_WARN("Received command message for ID 0x%lx for which we did not have an encoder.", can_id);
00112 }
00113 }
00114
00115
00116 void callback_headlight_set_cmd(const pacmod_msgs::PacmodCmd::ConstPtr& msg)
00117 {
00118 int64_t can_id = HeadlightCmdMsg::CAN_ID;
00119 auto rx_it = rx_list.find(can_id);
00120
00121 if (rx_it != rx_list.end())
00122 {
00123 rx_it->second->setData(PacmodRxRosMsgHandler::unpackAndEncode(can_id, msg));
00124 rx_it->second->setIsValid(true);
00125 }
00126 else
00127 {
00128 ROS_WARN("Received command message for ID 0x%lx for which we did not have an encoder.", can_id);
00129 }
00130 }
00131
00132
00133 void callback_horn_set_cmd(const pacmod_msgs::PacmodCmd::ConstPtr& msg)
00134 {
00135 int64_t can_id = HornCmdMsg::CAN_ID;
00136 auto rx_it = rx_list.find(can_id);
00137
00138 if (rx_it != rx_list.end())
00139 {
00140 rx_it->second->setData(PacmodRxRosMsgHandler::unpackAndEncode(can_id, msg));
00141 rx_it->second->setIsValid(true);
00142 }
00143 else
00144 {
00145 ROS_WARN("Received command message for ID 0x%lx for which we did not have an encoder.", can_id);
00146 }
00147 }
00148
00149
00150 void callback_wiper_set_cmd(const pacmod_msgs::PacmodCmd::ConstPtr& msg)
00151 {
00152 int64_t can_id = WiperCmdMsg::CAN_ID;
00153 auto rx_it = rx_list.find(can_id);
00154
00155 if (rx_it != rx_list.end())
00156 {
00157 rx_it->second->setData(PacmodRxRosMsgHandler::unpackAndEncode(can_id, msg));
00158 rx_it->second->setIsValid(true);
00159 }
00160 else
00161 {
00162 ROS_WARN("Received command message for ID 0x%lx for which we did not have an encoder.", can_id);
00163 }
00164 }
00165
00166
00167 void callback_shift_set_cmd(const pacmod_msgs::PacmodCmd::ConstPtr& msg)
00168 {
00169 int64_t can_id = ShiftCmdMsg::CAN_ID;
00170 auto rx_it = rx_list.find(can_id);
00171
00172 if (rx_it != rx_list.end())
00173 {
00174 rx_it->second->setData(PacmodRxRosMsgHandler::unpackAndEncode(can_id, msg));
00175 rx_it->second->setIsValid(true);
00176 }
00177 else
00178 {
00179 ROS_WARN("Received command message for ID 0x%lx for which we did not have an encoder.", can_id);
00180 }
00181 }
00182
00183
00184 void callback_accelerator_set_cmd(const pacmod_msgs::PacmodCmd::ConstPtr& msg)
00185 {
00186 int64_t can_id = AccelCmdMsg::CAN_ID;
00187 auto rx_it = rx_list.find(can_id);
00188
00189 if (rx_it != rx_list.end())
00190 {
00191 rx_it->second->setData(PacmodRxRosMsgHandler::unpackAndEncode(can_id, msg));
00192 rx_it->second->setIsValid(true);
00193 }
00194 else
00195 {
00196 ROS_WARN("Received command message for ID 0x%lx for which we did not have an encoder.", can_id);
00197 }
00198 }
00199
00200
00201 void callback_steering_set_cmd(const pacmod_msgs::PositionWithSpeed::ConstPtr& msg)
00202 {
00203 int64_t can_id = SteerCmdMsg::CAN_ID;
00204 auto rx_it = rx_list.find(can_id);
00205
00206 if (rx_it != rx_list.end())
00207 {
00208 rx_it->second->setData(PacmodRxRosMsgHandler::unpackAndEncode(can_id, msg));
00209 rx_it->second->setIsValid(true);
00210 }
00211 else
00212 {
00213 ROS_WARN("Received command message for ID 0x%lx for which we did not have an encoder.", can_id);
00214 }
00215 }
00216
00217
00218 void callback_brake_set_cmd(const pacmod_msgs::PacmodCmd::ConstPtr& msg)
00219 {
00220 int64_t can_id = BrakeCmdMsg::CAN_ID;
00221 auto rx_it = rx_list.find(can_id);
00222
00223 if (rx_it != rx_list.end())
00224 {
00225 rx_it->second->setData(PacmodRxRosMsgHandler::unpackAndEncode(can_id, msg));
00226 rx_it->second->setIsValid(true);
00227 }
00228 else
00229 {
00230 ROS_WARN("Received command message for ID 0x%lx for which we did not have an encoder.", can_id);
00231 }
00232 }
00233
00234 void send_can(int32_t id, const std::vector<unsigned char>& vec)
00235 {
00236 can_msgs::Frame frame;
00237 frame.id = id;
00238 frame.is_rtr = false;
00239 frame.is_extended = false;
00240 frame.is_error = false;
00241 frame.dlc = 8;
00242 std::copy(vec.begin(), vec.end(), frame.data.begin());
00243
00244 frame.header.stamp = ros::Time::now();
00245
00246 can_rx_pub.publish(frame);
00247 }
00248
00249 void can_write()
00250 {
00251 std::vector<unsigned char> data;
00252
00253 const std::chrono::milliseconds loop_pause = std::chrono::milliseconds(33);
00254 const std::chrono::milliseconds inter_msg_pause = std::chrono::milliseconds(1);
00255 bool keep_going = true;
00256
00257
00258 keep_going_mut.lock();
00259 keep_going = global_keep_going;
00260 keep_going_mut.unlock();
00261
00262 while (keep_going)
00263 {
00264
00265
00266
00267
00268
00269
00270
00271
00272
00273
00274
00275
00276
00277
00278
00279 GlobalCmdMsg global_obj;
00280 bool local_enable;
00281
00282 enable_mut.lock();
00283 local_enable = enable_state;
00284 enable_mut.unlock();
00285
00286 global_obj.encode(local_enable, true, false);
00287
00288
00289 send_can(GlobalCmdMsg::CAN_ID, global_obj.data);
00290
00291 std::this_thread::sleep_for(inter_msg_pause);
00292
00293 if (local_enable)
00294 {
00295
00296 for (const auto& element : rx_list)
00297 {
00298
00299 if (element.second->isValid())
00300 {
00301 send_can(element.first, element.second->getData());
00302 std::this_thread::sleep_for(inter_msg_pause);
00303 }
00304 }
00305 }
00306
00307 std::chrono::system_clock::time_point next_time = std::chrono::system_clock::now();
00308 next_time += loop_pause;
00309 std::this_thread::sleep_until(next_time);
00310
00311
00312 keep_going_mut.lock();
00313 keep_going = global_keep_going;
00314 keep_going_mut.unlock();
00315 }
00316 }
00317
00318 void can_read(const can_msgs::Frame::ConstPtr &msg)
00319 {
00320 std_msgs::Bool bool_pub_msg;
00321 auto parser_class = PacmodTxMsg::make_message(msg->id);
00322 auto pub = pub_tx_list.find(msg->id);
00323
00324
00325 if (parser_class != NULL && pub != pub_tx_list.end())
00326 {
00327 parser_class->parse(const_cast<unsigned char *>(&msg->data[0]));
00328 handler.fillAndPublish(msg->id, "pacmod", pub->second, parser_class);
00329
00330 bool local_enable = false;
00331
00332 enable_mut.lock();
00333 local_enable = enable_state;
00334 enable_mut.unlock();
00335
00336 if (!local_enable)
00337 {
00338
00339
00340
00341
00342
00343 auto cmd = rpt_cmd_list.find(msg->id);
00344
00345 if (cmd != rpt_cmd_list.end())
00346 {
00347
00348 auto rx_it = rx_list.find(cmd->second);
00349
00350 if (rx_it != rx_list.end())
00351 {
00352 if (msg->id == TurnSignalRptMsg::CAN_ID)
00353 {
00354 auto dc_parser = std::dynamic_pointer_cast<TurnSignalRptMsg>(parser_class);
00355 TurnSignalCmdMsg encoder;
00356
00357 encoder.encode(dc_parser->output);
00358 rx_it->second->setData(encoder.data);
00359 }
00360 else if (msg->id == ShiftRptMsg::CAN_ID)
00361 {
00362 auto dc_parser = std::dynamic_pointer_cast<ShiftRptMsg>(parser_class);
00363 ShiftCmdMsg encoder;
00364
00365 encoder.encode(dc_parser->output);
00366 rx_it->second->setData(encoder.data);
00367 }
00368 else if (msg->id == AccelRptMsg::CAN_ID)
00369 {
00370 auto dc_parser = std::dynamic_pointer_cast<AccelRptMsg>(parser_class);
00371 AccelCmdMsg encoder;
00372
00373 encoder.encode(dc_parser->output);
00374 rx_it->second->setData(encoder.data);
00375 }
00376 else if (msg->id == SteerRptMsg::CAN_ID)
00377 {
00378 auto dc_parser = std::dynamic_pointer_cast<SteerRptMsg>(parser_class);
00379 SteerCmdMsg encoder;
00380
00381 encoder.encode(dc_parser->output, 2.0);
00382 rx_it->second->setData(encoder.data);
00383 }
00384 else if (msg->id == BrakeRptMsg::CAN_ID)
00385 {
00386 auto dc_parser = std::dynamic_pointer_cast<BrakeRptMsg>(parser_class);
00387 BrakeCmdMsg encoder;
00388
00389 encoder.encode(dc_parser->output);
00390 rx_it->second->setData(encoder.data);
00391 }
00392 else if (msg->id == WiperRptMsg::CAN_ID)
00393 {
00394 auto dc_parser = std::dynamic_pointer_cast<WiperRptMsg>(parser_class);
00395 WiperCmdMsg encoder;
00396
00397 encoder.encode(dc_parser->output);
00398 rx_it->second->setData(encoder.data);
00399 }
00400 else if (msg->id == HornRptMsg::CAN_ID)
00401 {
00402 auto dc_parser = std::dynamic_pointer_cast<HornRptMsg>(parser_class);
00403 HornCmdMsg encoder;
00404
00405 encoder.encode(dc_parser->output);
00406 rx_it->second->setData(encoder.data);
00407 }
00408
00409 rx_it->second->setIsValid(true);
00410 }
00411 }
00412 }
00413
00414 if (msg->id == GlobalRptMsg::CAN_ID)
00415 {
00416 auto dc_parser = std::dynamic_pointer_cast<GlobalRptMsg>(parser_class);
00417
00418 bool_pub_msg.data = (dc_parser->enabled);
00419 enable_pub.publish(bool_pub_msg);
00420
00421 if (dc_parser->override_active)
00422 {
00423 set_enable(false);
00424 }
00425 }
00426 else if (msg->id == VehicleSpeedRptMsg::CAN_ID)
00427 {
00428 auto dc_parser = std::dynamic_pointer_cast<VehicleSpeedRptMsg>(parser_class);
00429
00430
00431 std_msgs::Float64 veh_spd_ms_msg;
00432 veh_spd_ms_msg.data = (dc_parser->vehicle_speed) * 0.44704;
00433 vehicle_speed_ms_pub.publish(veh_spd_ms_msg);
00434 }
00435 }
00436 }
00437
00438 int main(int argc, char *argv[])
00439 {
00440 ros::init(argc, argv, "pacmod");
00441 ros::AsyncSpinner spinner(2);
00442 ros::NodeHandle n;
00443 ros::NodeHandle priv("~");
00444 ros::Rate loop_rate(1.0);
00445
00446
00447 while (ros::Time::now().nsec == 0) {}
00448
00449
00450 if (priv.getParam("vehicle_type", veh_type_string))
00451 {
00452 ROS_INFO("PACMod - Got vehicle type of: %s", veh_type_string.c_str());
00453
00454 if (veh_type_string == "POLARIS_GEM")
00455 {
00456 veh_type = VehicleType::POLARIS_GEM;
00457 }
00458 else if (veh_type_string == "POLARIS_RANGER")
00459 {
00460 veh_type = VehicleType::POLARIS_RANGER;
00461 }
00462 else if (veh_type_string == "INTERNATIONAL_PROSTAR_122")
00463 {
00464 veh_type = VehicleType::INTERNATIONAL_PROSTAR_122;
00465 }
00466 else if (veh_type_string == "LEXUS_RX_450H")
00467 {
00468 veh_type = VehicleType::LEXUS_RX_450H;
00469 }
00470 else
00471 {
00472 veh_type = VehicleType::POLARIS_GEM;
00473 ROS_WARN("PACMod - An invalid vehicle type was entered. Assuming POLARIS_GEM.");
00474 }
00475 }
00476
00477
00478 can_rx_pub = n.advertise<can_msgs::Frame>("can_rx", 20);
00479 global_rpt_pub = n.advertise<pacmod_msgs::GlobalRpt>("parsed_tx/global_rpt", 20);
00480 vin_rpt_pub = n.advertise<pacmod_msgs::VinRpt>("parsed_tx/vin_rpt", 5);
00481 turn_rpt_pub = n.advertise<pacmod_msgs::SystemRptInt>("parsed_tx/turn_rpt", 20);
00482 shift_rpt_pub = n.advertise<pacmod_msgs::SystemRptInt>("parsed_tx/shift_rpt", 20);
00483 accel_rpt_pub = n.advertise<pacmod_msgs::SystemRptFloat>("parsed_tx/accel_rpt", 20);
00484 steer_rpt_pub = n.advertise<pacmod_msgs::SystemRptFloat>("parsed_tx/steer_rpt", 20);
00485 brake_rpt_pub = n.advertise<pacmod_msgs::SystemRptFloat>("parsed_tx/brake_rpt", 20);
00486 vehicle_speed_pub = n.advertise<pacmod_msgs::VehicleSpeedRpt>("parsed_tx/vehicle_speed_rpt", 20);
00487 vehicle_speed_ms_pub = n.advertise<std_msgs::Float64>("as_tx/vehicle_speed", 20);
00488 enable_pub = n.advertise<std_msgs::Bool>("as_tx/enable", 20, true);
00489
00490 std::string frame_id = "pacmod";
00491
00492
00493 pub_tx_list.insert(std::make_pair(GlobalRptMsg::CAN_ID, global_rpt_pub));
00494 pub_tx_list.insert(std::make_pair(VinRptMsg::CAN_ID, vin_rpt_pub));
00495 pub_tx_list.insert(std::make_pair(TurnSignalRptMsg::CAN_ID, turn_rpt_pub));
00496 pub_tx_list.insert(std::make_pair(ShiftRptMsg::CAN_ID, shift_rpt_pub));
00497 pub_tx_list.insert(std::make_pair(AccelRptMsg::CAN_ID, accel_rpt_pub));
00498 pub_tx_list.insert(std::make_pair(SteerRptMsg::CAN_ID, steer_rpt_pub));
00499 pub_tx_list.insert(std::make_pair(BrakeRptMsg::CAN_ID, brake_rpt_pub));
00500 pub_tx_list.insert(std::make_pair(VehicleSpeedRptMsg::CAN_ID, vehicle_speed_pub));
00501
00502
00503 ros::Subscriber can_tx_sub = n.subscribe("can_tx", 20, can_read);
00504 ros::Subscriber turn_set_cmd_sub = n.subscribe("as_rx/turn_cmd", 20, callback_turn_signal_set_cmd);
00505 ros::Subscriber shift_set_cmd_sub = n.subscribe("as_rx/shift_cmd", 20, callback_shift_set_cmd);
00506 ros::Subscriber accelerator_set_cmd = n.subscribe("as_rx/accel_cmd", 20, callback_accelerator_set_cmd);
00507 ros::Subscriber steering_set_cmd = n.subscribe("as_rx/steer_cmd", 20, callback_steering_set_cmd);
00508 ros::Subscriber brake_set_cmd = n.subscribe("as_rx/brake_cmd", 20, callback_brake_set_cmd);
00509 ros::Subscriber enable_sub = n.subscribe("as_rx/enable", 20, callback_pacmod_enable);
00510
00511
00512 std::shared_ptr<LockedData> global_data(new LockedData);
00513 std::shared_ptr<LockedData> turn_data(new LockedData);
00514 std::shared_ptr<LockedData> shift_data(new LockedData);
00515 std::shared_ptr<LockedData> accel_data(new LockedData);
00516 std::shared_ptr<LockedData> steer_data(new LockedData);
00517 std::shared_ptr<LockedData> brake_data(new LockedData);
00518
00519 rx_list.insert(std::make_pair(GlobalCmdMsg::CAN_ID, global_data));
00520 rx_list.insert(std::make_pair(TurnSignalCmdMsg::CAN_ID, turn_data));
00521 rx_list.insert(std::make_pair(ShiftCmdMsg::CAN_ID, shift_data));
00522 rx_list.insert(std::make_pair(AccelCmdMsg::CAN_ID, accel_data));
00523 rx_list.insert(std::make_pair(SteerCmdMsg::CAN_ID, steer_data));
00524 rx_list.insert(std::make_pair(BrakeCmdMsg::CAN_ID, brake_data));
00525
00526 if (veh_type == VehicleType::POLARIS_GEM ||
00527 veh_type == VehicleType::POLARIS_RANGER ||
00528 veh_type == VehicleType::INTERNATIONAL_PROSTAR_122)
00529 {
00530 brake_rpt_detail_1_pub = n.advertise<pacmod_msgs::MotorRpt1>("parsed_tx/brake_rpt_detail_1", 20);
00531 brake_rpt_detail_2_pub = n.advertise<pacmod_msgs::MotorRpt2>("parsed_tx/brake_rpt_detail_2", 20);
00532 brake_rpt_detail_3_pub = n.advertise<pacmod_msgs::MotorRpt3>("parsed_tx/brake_rpt_detail_3", 20);
00533 steering_rpt_detail_1_pub = n.advertise<pacmod_msgs::MotorRpt1>("parsed_tx/steer_rpt_detail_1", 20);
00534 steering_rpt_detail_2_pub = n.advertise<pacmod_msgs::MotorRpt2>("parsed_tx/steer_rpt_detail_2", 20);
00535 steering_rpt_detail_3_pub = n.advertise<pacmod_msgs::MotorRpt3>("parsed_tx/steer_rpt_detail_3", 20);
00536
00537 pub_tx_list.insert(std::make_pair(BrakeMotorRpt1Msg::CAN_ID, brake_rpt_detail_1_pub));
00538 pub_tx_list.insert(std::make_pair(BrakeMotorRpt2Msg::CAN_ID, brake_rpt_detail_2_pub));
00539 pub_tx_list.insert(std::make_pair(BrakeMotorRpt3Msg::CAN_ID, brake_rpt_detail_3_pub));
00540 pub_tx_list.insert(std::make_pair(SteerMotorRpt1Msg::CAN_ID, steering_rpt_detail_1_pub));
00541 pub_tx_list.insert(std::make_pair(SteerMotorRpt2Msg::CAN_ID, steering_rpt_detail_2_pub));
00542 pub_tx_list.insert(std::make_pair(SteerMotorRpt3Msg::CAN_ID, steering_rpt_detail_3_pub));
00543 }
00544
00545 if (veh_type == VehicleType::INTERNATIONAL_PROSTAR_122)
00546 {
00547 wiper_rpt_pub = n.advertise<pacmod_msgs::SystemRptInt>("parsed_tx/wiper_rpt", 20);
00548
00549 pub_tx_list.insert(std::make_pair(WiperRptMsg::CAN_ID, wiper_rpt_pub));
00550
00551 wiper_set_cmd_sub = std::shared_ptr<ros::Subscriber>(new ros::Subscriber(n.subscribe("as_rx/wiper_cmd",
00552 20,
00553 callback_wiper_set_cmd)));
00554
00555 std::shared_ptr<LockedData> wiper_data(new LockedData);
00556 rx_list.insert(std::make_pair(WiperCmdMsg::CAN_ID, wiper_data));
00557 }
00558
00559 if (veh_type == VehicleType::LEXUS_RX_450H)
00560 {
00561 horn_rpt_pub = n.advertise<pacmod_msgs::SystemRptInt>("parsed_tx/horn_rpt", 20);
00562 steer_rpt_2_pub = n.advertise<pacmod_msgs::SystemRptFloat>("parsed_tx/steer_rpt_2", 20);
00563 steer_rpt_3_pub = n.advertise<pacmod_msgs::SystemRptFloat>("parsed_tx/steer_rpt_3", 20);
00564 wheel_speed_rpt_pub = n.advertise<pacmod_msgs::WheelSpeedRpt>("parsed_tx/wheel_speed_rpt", 20);
00565 steering_pid_rpt_1_pub = n.advertise<pacmod_msgs::SteeringPIDRpt1>("parsed_tx/steer_pid_rpt_1", 20);
00566 steering_pid_rpt_2_pub = n.advertise<pacmod_msgs::SteeringPIDRpt2>("parsed_tx/steer_pid_rpt_2", 20);
00567 steering_pid_rpt_3_pub = n.advertise<pacmod_msgs::SteeringPIDRpt3>("parsed_tx/steer_pid_rpt_3", 20);
00568 steering_pid_rpt_4_pub = n.advertise<pacmod_msgs::SteeringPIDRpt4>("parsed_tx/steer_pid_rpt_4", 20);
00569 yaw_rate_rpt_pub = n.advertise<pacmod_msgs::YawRateRpt>("parsed_tx/yaw_rate_rpt", 20);
00570 lat_lon_heading_rpt_pub = n.advertise<pacmod_msgs::LatLonHeadingRpt>("parsed_tx/lat_lon_heading_rpt", 20);
00571 date_time_rpt_pub = n.advertise<pacmod_msgs::DateTimeRpt>("parsed_tx/date_time_rpt", 20);
00572
00573 pub_tx_list.insert(std::make_pair(HornRptMsg::CAN_ID, horn_rpt_pub));
00574 pub_tx_list.insert(std::make_pair(SteerRpt2Msg::CAN_ID, steer_rpt_2_pub));
00575 pub_tx_list.insert(std::make_pair(SteerRpt3Msg::CAN_ID, steer_rpt_3_pub));
00576 pub_tx_list.insert(std::make_pair(WheelSpeedRptMsg::CAN_ID, wheel_speed_rpt_pub));
00577 pub_tx_list.insert(std::make_pair(SteeringPIDRpt1Msg::CAN_ID, steering_pid_rpt_1_pub));
00578 pub_tx_list.insert(std::make_pair(SteeringPIDRpt2Msg::CAN_ID, steering_pid_rpt_2_pub));
00579 pub_tx_list.insert(std::make_pair(SteeringPIDRpt3Msg::CAN_ID, steering_pid_rpt_3_pub));
00580 pub_tx_list.insert(std::make_pair(SteeringPIDRpt4Msg::CAN_ID, steering_pid_rpt_4_pub));
00581 pub_tx_list.insert(std::make_pair(YawRateRptMsg::CAN_ID, yaw_rate_rpt_pub));
00582 pub_tx_list.insert(std::make_pair(LatLonHeadingRptMsg::CAN_ID, lat_lon_heading_rpt_pub));
00583 pub_tx_list.insert(std::make_pair(DateTimeRptMsg::CAN_ID, date_time_rpt_pub));
00584
00585 headlight_set_cmd_sub =
00586 std::shared_ptr<ros::Subscriber>(new ros::Subscriber(n.subscribe("as_rx/headlight_cmd",
00587 20,
00588 callback_headlight_set_cmd)));
00589 horn_set_cmd_sub =
00590 std::shared_ptr<ros::Subscriber>(new ros::Subscriber(n.subscribe("as_rx/horn_cmd",
00591 20,
00592 callback_horn_set_cmd)));
00593
00594 std::shared_ptr<LockedData> headlight_data(new LockedData);
00595 std::shared_ptr<LockedData> horn_data(new LockedData);
00596
00597 rx_list.insert(std::make_pair(HeadlightCmdMsg::CAN_ID, headlight_data));
00598 rx_list.insert(std::make_pair(HornCmdMsg::CAN_ID, horn_data));
00599 }
00600
00601 if (veh_type == VehicleType::LEXUS_RX_450H)
00602 {
00603 headlight_rpt_pub = n.advertise<pacmod_msgs::SystemRptInt>("parsed_tx/headlight_rpt", 20);
00604 parking_brake_status_rpt_pub =
00605 n.advertise<pacmod_msgs::ParkingBrakeStatusRpt>("parsed_tx/parking_brake_status_rpt", 20);
00606
00607 pub_tx_list.insert(std::make_pair(HeadlightRptMsg::CAN_ID, headlight_rpt_pub));
00608 pub_tx_list.insert(std::make_pair(ParkingBrakeStatusRptMsg::CAN_ID, parking_brake_status_rpt_pub));
00609 }
00610
00611
00612 rpt_cmd_list.insert(std::make_pair(TurnSignalRptMsg::CAN_ID, TurnSignalCmdMsg::CAN_ID));
00613 rpt_cmd_list.insert(std::make_pair(ShiftRptMsg::CAN_ID, ShiftCmdMsg::CAN_ID));
00614 rpt_cmd_list.insert(std::make_pair(AccelRptMsg::CAN_ID, AccelCmdMsg::CAN_ID));
00615 rpt_cmd_list.insert(std::make_pair(SteerRptMsg::CAN_ID, SteerCmdMsg::CAN_ID));
00616 rpt_cmd_list.insert(std::make_pair(BrakeRptMsg::CAN_ID, BrakeCmdMsg::CAN_ID));
00617
00618 if (veh_type == VehicleType::INTERNATIONAL_PROSTAR_122)
00619 {
00620 rpt_cmd_list.insert(std::make_pair(WiperRptMsg::CAN_ID, WiperCmdMsg::CAN_ID));
00621 }
00622 else if (veh_type == VehicleType::LEXUS_RX_450H)
00623 {
00624 rpt_cmd_list.insert(std::make_pair(HornRptMsg::CAN_ID, HornCmdMsg::CAN_ID));
00625 }
00626
00627
00628 set_enable(false);
00629
00630
00631 std::thread can_write_thread(can_write);
00632
00633 spinner.start();
00634
00635 ros::waitForShutdown();
00636
00637
00638 set_enable(false);
00639
00640 keep_going_mut.lock();
00641 global_keep_going = false;
00642 keep_going_mut.unlock();
00643
00644 can_write_thread.join();
00645
00646 return 0;
00647 }
00648