13 #include <unordered_map> 15 #include <std_msgs/Int16.h> 16 #include <std_msgs/Bool.h> 17 #include <std_msgs/Float64.h> 18 #include <can_msgs/Frame.h> 69 std::unordered_map<int64_t, std::shared_ptr<LockedData>>
rx_list;
102 auto rx_it =
rx_list.find(can_id);
107 rx_it->second->setIsValid(
true);
111 ROS_WARN(
"Received command message for ID 0x%lx for which we did not have an encoder.", can_id);
119 auto rx_it =
rx_list.find(can_id);
124 rx_it->second->setIsValid(
true);
128 ROS_WARN(
"Received command message for ID 0x%lx for which we did not have an encoder.", can_id);
136 auto rx_it =
rx_list.find(can_id);
141 rx_it->second->setIsValid(
true);
145 ROS_WARN(
"Received command message for ID 0x%lx for which we did not have an encoder.", can_id);
153 auto rx_it =
rx_list.find(can_id);
158 rx_it->second->setIsValid(
true);
162 ROS_WARN(
"Received command message for ID 0x%lx for which we did not have an encoder.", can_id);
170 auto rx_it =
rx_list.find(can_id);
175 rx_it->second->setIsValid(
true);
179 ROS_WARN(
"Received command message for ID 0x%lx for which we did not have an encoder.", can_id);
187 auto rx_it =
rx_list.find(can_id);
192 rx_it->second->setIsValid(
true);
196 ROS_WARN(
"Received command message for ID 0x%lx for which we did not have an encoder.", can_id);
204 auto rx_it =
rx_list.find(can_id);
209 rx_it->second->setIsValid(
true);
213 ROS_WARN(
"Received command message for ID 0x%lx for which we did not have an encoder.", can_id);
221 auto rx_it =
rx_list.find(can_id);
226 rx_it->second->setIsValid(
true);
230 ROS_WARN(
"Received command message for ID 0x%lx for which we did not have an encoder.", can_id);
234 void send_can(int32_t
id,
const std::vector<unsigned char>& vec)
236 can_msgs::Frame frame;
238 frame.is_rtr =
false;
239 frame.is_extended =
false;
240 frame.is_error =
false;
242 std::copy(vec.begin(), vec.end(), frame.data.begin());
251 std::vector<unsigned char> data;
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;
286 global_obj.
encode(local_enable,
true,
false);
291 std::this_thread::sleep_for(inter_msg_pause);
296 for (
const auto& element :
rx_list)
299 if (element.second->isValid())
301 send_can(element.first, element.second->getData());
302 std::this_thread::sleep_for(inter_msg_pause);
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);
318 void can_read(
const can_msgs::Frame::ConstPtr &msg)
320 std_msgs::Bool bool_pub_msg;
325 if (parser_class != NULL && pub !=
pub_tx_list.end())
327 parser_class->parse(const_cast<unsigned char *>(&msg->data[0]));
328 handler.
fillAndPublish(msg->id,
"pacmod", pub->second, parser_class);
330 bool local_enable =
false;
348 auto rx_it =
rx_list.find(cmd->second);
357 encoder.
encode(dc_parser->output);
358 rx_it->second->setData(encoder.data);
362 auto dc_parser = std::dynamic_pointer_cast<
ShiftRptMsg>(parser_class);
365 encoder.
encode(dc_parser->output);
366 rx_it->second->setData(encoder.data);
370 auto dc_parser = std::dynamic_pointer_cast<
AccelRptMsg>(parser_class);
373 encoder.
encode(dc_parser->output);
374 rx_it->second->setData(encoder.data);
378 auto dc_parser = std::dynamic_pointer_cast<
SteerRptMsg>(parser_class);
381 encoder.
encode(dc_parser->output, 2.0);
382 rx_it->second->setData(encoder.data);
386 auto dc_parser = std::dynamic_pointer_cast<
BrakeRptMsg>(parser_class);
389 encoder.
encode(dc_parser->output);
390 rx_it->second->setData(encoder.data);
394 auto dc_parser = std::dynamic_pointer_cast<
WiperRptMsg>(parser_class);
397 encoder.
encode(dc_parser->output);
398 rx_it->second->setData(encoder.data);
402 auto dc_parser = std::dynamic_pointer_cast<
HornRptMsg>(parser_class);
405 encoder.
encode(dc_parser->output);
406 rx_it->second->setData(encoder.data);
409 rx_it->second->setIsValid(
true);
416 auto dc_parser = std::dynamic_pointer_cast<
GlobalRptMsg>(parser_class);
418 bool_pub_msg.data = (dc_parser->enabled);
419 enable_pub.
publish(bool_pub_msg);
421 if (dc_parser->override_active)
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);
438 int main(
int argc,
char *argv[])
473 ROS_WARN(
"PACMod - An invalid vehicle type was entered. Assuming POLARIS_GEM.");
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);
490 std::string frame_id =
"pacmod";
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);
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);
547 wiper_rpt_pub = n.
advertise<pacmod_msgs::SystemRptInt>(
"parsed_tx/wiper_rpt", 20);
555 std::shared_ptr<LockedData> wiper_data(
new LockedData);
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);
594 std::shared_ptr<LockedData> headlight_data(
new LockedData);
595 std::shared_ptr<LockedData> horn_data(
new LockedData);
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);
644 can_write_thread.join();
void set_enable(bool val)
ros::Publisher steering_rpt_detail_2_pub
ros::Publisher accel_rpt_pub
static const int64_t CAN_ID
void encode(uint8_t horn_cmd)
ros::Publisher headlight_rpt_pub
void callback_pacmod_enable(const std_msgs::Bool::ConstPtr &msg)
std::unordered_map< int64_t, std::shared_ptr< LockedData > > rx_list
ros::Publisher vin_rpt_pub
void can_read(const can_msgs::Frame::ConstPtr &msg)
ros::Publisher yaw_rate_rpt_pub
static const int64_t CAN_ID
void publish(const boost::shared_ptr< M > &message) const
const double watchdog_timeout
ros::Publisher date_time_rpt_pub
static const int64_t CAN_ID
std::shared_ptr< ros::Subscriber > wiper_set_cmd_sub
Subscriber subscribe(const std::string &topic, uint32_t queue_size, void(T::*fp)(M), T *obj, const TransportHints &transport_hints=TransportHints())
static const int64_t CAN_ID
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)
static const int64_t CAN_ID
std::unordered_map< int64_t, int64_t > rpt_cmd_list
ros::Publisher steer_rpt_pub
static const int64_t CAN_ID
ROSCPP_DECL void init(int &argc, char **argv, const std::string &name, uint32_t options=0)
ros::Publisher vehicle_speed_ms_pub
double last_global_rpt_msg_received
static const int64_t CAN_ID
static const int64_t CAN_ID
static const int64_t CAN_ID
ros::Publisher steering_pid_rpt_2_pub
ros::Publisher turn_rpt_pub
static const int64_t CAN_ID
ros::Publisher can_rx_pub
void callback_wiper_set_cmd(const pacmod_msgs::PacmodCmd::ConstPtr &msg)
ros::Publisher steer_rpt_3_pub
void encode(double steer_pos, double steer_spd)
ros::Publisher steering_pid_rpt_3_pub
static const int64_t CAN_ID
static const int64_t CAN_ID
static const int64_t CAN_ID
ros::Publisher steering_rpt_detail_1_pub
ros::Publisher steering_pid_rpt_1_pub
static const int64_t CAN_ID
static const int64_t CAN_ID
void encode(double accel_cmd)
std::vector< uint8_t > data
void encode(uint8_t wiper_cmd)
ros::Publisher brake_rpt_detail_3_pub
int main(int argc, char *argv[])
ros::Publisher wiper_rpt_pub
ros::Publisher shift_rpt_pub
std::string veh_type_string
void encode(double brake_cmd)
void encode(uint8_t turn_signal_cmd)
void encode(uint8_t shift_cmd)
static const int64_t CAN_ID
static const int64_t CAN_ID
ros::Publisher horn_rpt_pub
static const int64_t CAN_ID
ros::Publisher wheel_speed_rpt_pub
static const int64_t CAN_ID
void callback_brake_set_cmd(const pacmod_msgs::PacmodCmd::ConstPtr &msg)
void callback_shift_set_cmd(const pacmod_msgs::PacmodCmd::ConstPtr &msg)
static const int64_t CAN_ID
ros::Publisher steering_pid_rpt_4_pub
static const int64_t CAN_ID
static const int64_t CAN_ID
static const int64_t CAN_ID
ros::Publisher steer_rpt_2_pub
std::chrono::milliseconds can_error_pause
ros::Publisher parking_brake_status_rpt_pub
Publisher advertise(const std::string &topic, uint32_t queue_size, bool latch=false)
ros::Publisher brake_rpt_detail_1_pub
void callback_horn_set_cmd(const pacmod_msgs::PacmodCmd::ConstPtr &msg)
ros::Publisher enable_pub
static const int64_t CAN_ID
std::shared_ptr< ros::Subscriber > horn_set_cmd_sub
static const int64_t CAN_ID
PacmodTxRosMsgHandler handler
ros::Publisher brake_rpt_detail_2_pub
static const int64_t CAN_ID
static const int64_t CAN_ID
static const int64_t CAN_ID
ros::Publisher vehicle_speed_pub
static const int64_t CAN_ID
ros::Publisher global_rpt_pub
bool getParam(const std::string &key, std::string &s) const
static const int64_t CAN_ID
static const int64_t CAN_ID
static const int64_t CAN_ID
ros::Publisher lat_lon_heading_rpt_pub
ros::Publisher steering_rpt_detail_3_pub
void send_can(int32_t id, const std::vector< unsigned char > &vec)
ros::Publisher brake_rpt_pub
static const int64_t CAN_ID
void fillAndPublish(const int64_t &can_id, std::string frame_id, const ros::Publisher &pub, const std::shared_ptr< PacmodTxMsg > &parser_class)
static const int64_t CAN_ID
static std::shared_ptr< PacmodTxMsg > make_message(const int64_t &can_id)
std::mutex keep_going_mut
static const int64_t CAN_ID
static const int64_t CAN_ID
std::unordered_map< int64_t, ros::Publisher > pub_tx_list
static const int64_t CAN_ID
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
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)