#include <pacmod3_ros_msg_handler.h>
Public Member Functions | |
void | fillAndPublish (const int64_t &can_id, std::string frame_id, ros::Publisher &pub, std::shared_ptr< Pacmod3TxMsg > &parser_class) |
Private Member Functions | |
void | fillAccelAuxRpt (std::shared_ptr< Pacmod3TxMsg > &parser_class, pacmod_msgs::AccelAuxRpt &new_msg, std::string frame_id) |
void | fillBrakeAuxRpt (std::shared_ptr< Pacmod3TxMsg > &parser_class, pacmod_msgs::BrakeAuxRpt &new_msg, std::string frame_id) |
void | fillDateTimeRpt (std::shared_ptr< Pacmod3TxMsg > &parser_class, pacmod_msgs::DateTimeRpt &new_msg, std::string frame_id) |
void | fillDetectedObjectRpt (std::shared_ptr< Pacmod3TxMsg > &parser_class, pacmod_msgs::DetectedObjectRpt &new_msg, std::string frame_id) |
void | fillDoorRpt (std::shared_ptr< Pacmod3TxMsg > &parser_class, pacmod_msgs::DoorRpt &new_msg, std::string frame_id) |
void | fillGlobalRpt (std::shared_ptr< Pacmod3TxMsg > &parser_class, pacmod_msgs::GlobalRpt &new_msg, std::string frame_id) |
void | fillHeadlightAuxRpt (std::shared_ptr< Pacmod3TxMsg > &parser_class, pacmod_msgs::HeadlightAuxRpt &new_msg, std::string frame_id) |
void | fillInteriorLightsRpt (std::shared_ptr< Pacmod3TxMsg > &parser_class, pacmod_msgs::InteriorLightsRpt &new_msg, std::string frame_id) |
void | fillLatLonHeadingRpt (std::shared_ptr< Pacmod3TxMsg > &parser_class, pacmod_msgs::LatLonHeadingRpt &new_msg, std::string frame_id) |
void | fillMotorRpt1 (std::shared_ptr< Pacmod3TxMsg > &parser_class, pacmod_msgs::MotorRpt1 &new_msg, std::string frame_id) |
void | fillMotorRpt2 (std::shared_ptr< Pacmod3TxMsg > &parser_class, pacmod_msgs::MotorRpt2 &new_msg, std::string frame_id) |
void | fillMotorRpt3 (std::shared_ptr< Pacmod3TxMsg > &parser_class, pacmod_msgs::MotorRpt3 &new_msg, std::string frame_id) |
void | fillOccupancyRpt (std::shared_ptr< Pacmod3TxMsg > &parser_class, pacmod_msgs::OccupancyRpt &new_msg, std::string frame_id) |
void | fillRearLightsRpt (std::shared_ptr< Pacmod3TxMsg > &parser_class, pacmod_msgs::RearLightsRpt &new_msg, std::string frame_id) |
void | fillShiftAuxRpt (std::shared_ptr< Pacmod3TxMsg > &parser_class, pacmod_msgs::ShiftAuxRpt &new_msg, std::string frame_id) |
void | fillSteerAuxRpt (std::shared_ptr< Pacmod3TxMsg > &parser_class, pacmod_msgs::SteerAuxRpt &new_msg, std::string frame_id) |
void | fillSteeringPIDRpt1 (std::shared_ptr< Pacmod3TxMsg > &parser_class, pacmod_msgs::SteeringPIDRpt1 &new_msg, std::string frame_id) |
void | fillSteeringPIDRpt2 (std::shared_ptr< Pacmod3TxMsg > &parser_class, pacmod_msgs::SteeringPIDRpt2 &new_msg, std::string frame_id) |
void | fillSteeringPIDRpt3 (std::shared_ptr< Pacmod3TxMsg > &parser_class, pacmod_msgs::SteeringPIDRpt3 &new_msg, std::string frame_id) |
void | fillSteeringPIDRpt4 (std::shared_ptr< Pacmod3TxMsg > &parser_class, pacmod_msgs::SteeringPIDRpt4 &new_msg, std::string frame_id) |
void | fillSystemRptBool (std::shared_ptr< Pacmod3TxMsg > &parser_class, pacmod_msgs::SystemRptBool &new_msg, std::string frame_id) |
void | fillSystemRptFloat (std::shared_ptr< Pacmod3TxMsg > &parser_class, pacmod_msgs::SystemRptFloat &new_msg, std::string frame_id) |
void | fillSystemRptInt (std::shared_ptr< Pacmod3TxMsg > &parser_class, pacmod_msgs::SystemRptInt &new_msg, std::string frame_id) |
void | fillTurnAuxRpt (std::shared_ptr< Pacmod3TxMsg > &parser_class, pacmod_msgs::TurnAuxRpt &new_msg, std::string frame_id) |
void | fillVehicleDynamicsRpt (std::shared_ptr< Pacmod3TxMsg > &parser_class, pacmod_msgs::VehicleDynamicsRpt &new_msg, std::string frame_id) |
void | fillVehicleSpecificRpt1 (std::shared_ptr< Pacmod3TxMsg > &parser_class, pacmod_msgs::VehicleSpecificRpt1 &new_msg, std::string frame_id) |
void | fillVehicleSpeedRpt (std::shared_ptr< Pacmod3TxMsg > &parser_class, pacmod_msgs::VehicleSpeedRpt &new_msg, std::string frame_id) |
void | fillVinRpt (std::shared_ptr< Pacmod3TxMsg > &parser_class, pacmod_msgs::VinRpt &new_msg, std::string frame_id) |
void | fillWheelSpeedRpt (std::shared_ptr< Pacmod3TxMsg > &parser_class, pacmod_msgs::WheelSpeedRpt &new_msg, std::string frame_id) |
void | fillWiperAuxRpt (std::shared_ptr< Pacmod3TxMsg > &parser_class, pacmod_msgs::WiperAuxRpt &new_msg, std::string frame_id) |
void | fillYawRateRpt (std::shared_ptr< Pacmod3TxMsg > &parser_class, pacmod_msgs::YawRateRpt &new_msg, std::string frame_id) |
Definition at line 32 of file pacmod3_ros_msg_handler.h.
void Pacmod3TxRosMsgHandler::fillAccelAuxRpt | ( | std::shared_ptr< Pacmod3TxMsg > & | parser_class, |
pacmod_msgs::AccelAuxRpt & | new_msg, | ||
std::string | frame_id | ||
) | [private] |
Definition at line 316 of file pacmod3_ros_msg_handler.cpp.
void Pacmod3TxRosMsgHandler::fillAndPublish | ( | const int64_t & | can_id, |
std::string | frame_id, | ||
ros::Publisher & | pub, | ||
std::shared_ptr< Pacmod3TxMsg > & | parser_class | ||
) |
Definition at line 30 of file pacmod3_ros_msg_handler.cpp.
void Pacmod3TxRosMsgHandler::fillBrakeAuxRpt | ( | std::shared_ptr< Pacmod3TxMsg > & | parser_class, |
pacmod_msgs::BrakeAuxRpt & | new_msg, | ||
std::string | frame_id | ||
) | [private] |
Definition at line 331 of file pacmod3_ros_msg_handler.cpp.
void Pacmod3TxRosMsgHandler::fillDateTimeRpt | ( | std::shared_ptr< Pacmod3TxMsg > & | parser_class, |
pacmod_msgs::DateTimeRpt & | new_msg, | ||
std::string | frame_id | ||
) | [private] |
Definition at line 349 of file pacmod3_ros_msg_handler.cpp.
void Pacmod3TxRosMsgHandler::fillDetectedObjectRpt | ( | std::shared_ptr< Pacmod3TxMsg > & | parser_class, |
pacmod_msgs::DetectedObjectRpt & | new_msg, | ||
std::string | frame_id | ||
) | [private] |
Definition at line 364 of file pacmod3_ros_msg_handler.cpp.
void Pacmod3TxRosMsgHandler::fillDoorRpt | ( | std::shared_ptr< Pacmod3TxMsg > & | parser_class, |
pacmod_msgs::DoorRpt & | new_msg, | ||
std::string | frame_id | ||
) | [private] |
Definition at line 374 of file pacmod3_ros_msg_handler.cpp.
void Pacmod3TxRosMsgHandler::fillGlobalRpt | ( | std::shared_ptr< Pacmod3TxMsg > & | parser_class, |
pacmod_msgs::GlobalRpt & | new_msg, | ||
std::string | frame_id | ||
) | [private] |
Definition at line 297 of file pacmod3_ros_msg_handler.cpp.
void Pacmod3TxRosMsgHandler::fillHeadlightAuxRpt | ( | std::shared_ptr< Pacmod3TxMsg > & | parser_class, |
pacmod_msgs::HeadlightAuxRpt & | new_msg, | ||
std::string | frame_id | ||
) | [private] |
Definition at line 397 of file pacmod3_ros_msg_handler.cpp.
void Pacmod3TxRosMsgHandler::fillInteriorLightsRpt | ( | std::shared_ptr< Pacmod3TxMsg > & | parser_class, |
pacmod_msgs::InteriorLightsRpt & | new_msg, | ||
std::string | frame_id | ||
) | [private] |
Definition at line 414 of file pacmod3_ros_msg_handler.cpp.
void Pacmod3TxRosMsgHandler::fillLatLonHeadingRpt | ( | std::shared_ptr< Pacmod3TxMsg > & | parser_class, |
pacmod_msgs::LatLonHeadingRpt & | new_msg, | ||
std::string | frame_id | ||
) | [private] |
Definition at line 431 of file pacmod3_ros_msg_handler.cpp.
void Pacmod3TxRosMsgHandler::fillMotorRpt1 | ( | std::shared_ptr< Pacmod3TxMsg > & | parser_class, |
pacmod_msgs::MotorRpt1 & | new_msg, | ||
std::string | frame_id | ||
) | [private] |
Definition at line 447 of file pacmod3_ros_msg_handler.cpp.
void Pacmod3TxRosMsgHandler::fillMotorRpt2 | ( | std::shared_ptr< Pacmod3TxMsg > & | parser_class, |
pacmod_msgs::MotorRpt2 & | new_msg, | ||
std::string | frame_id | ||
) | [private] |
Definition at line 458 of file pacmod3_ros_msg_handler.cpp.
void Pacmod3TxRosMsgHandler::fillMotorRpt3 | ( | std::shared_ptr< Pacmod3TxMsg > & | parser_class, |
pacmod_msgs::MotorRpt3 & | new_msg, | ||
std::string | frame_id | ||
) | [private] |
Definition at line 470 of file pacmod3_ros_msg_handler.cpp.
void Pacmod3TxRosMsgHandler::fillOccupancyRpt | ( | std::shared_ptr< Pacmod3TxMsg > & | parser_class, |
pacmod_msgs::OccupancyRpt & | new_msg, | ||
std::string | frame_id | ||
) | [private] |
Definition at line 481 of file pacmod3_ros_msg_handler.cpp.
void Pacmod3TxRosMsgHandler::fillRearLightsRpt | ( | std::shared_ptr< Pacmod3TxMsg > & | parser_class, |
pacmod_msgs::RearLightsRpt & | new_msg, | ||
std::string | frame_id | ||
) | [private] |
Definition at line 502 of file pacmod3_ros_msg_handler.cpp.
void Pacmod3TxRosMsgHandler::fillShiftAuxRpt | ( | std::shared_ptr< Pacmod3TxMsg > & | parser_class, |
pacmod_msgs::ShiftAuxRpt & | new_msg, | ||
std::string | frame_id | ||
) | [private] |
Definition at line 515 of file pacmod3_ros_msg_handler.cpp.
void Pacmod3TxRosMsgHandler::fillSteerAuxRpt | ( | std::shared_ptr< Pacmod3TxMsg > & | parser_class, |
pacmod_msgs::SteerAuxRpt & | new_msg, | ||
std::string | frame_id | ||
) | [private] |
Definition at line 532 of file pacmod3_ros_msg_handler.cpp.
void Pacmod3TxRosMsgHandler::fillSteeringPIDRpt1 | ( | std::shared_ptr< Pacmod3TxMsg > & | parser_class, |
pacmod_msgs::SteeringPIDRpt1 & | new_msg, | ||
std::string | frame_id | ||
) | [private] |
Definition at line 549 of file pacmod3_ros_msg_handler.cpp.
void Pacmod3TxRosMsgHandler::fillSteeringPIDRpt2 | ( | std::shared_ptr< Pacmod3TxMsg > & | parser_class, |
pacmod_msgs::SteeringPIDRpt2 & | new_msg, | ||
std::string | frame_id | ||
) | [private] |
Definition at line 562 of file pacmod3_ros_msg_handler.cpp.
void Pacmod3TxRosMsgHandler::fillSteeringPIDRpt3 | ( | std::shared_ptr< Pacmod3TxMsg > & | parser_class, |
pacmod_msgs::SteeringPIDRpt3 & | new_msg, | ||
std::string | frame_id | ||
) | [private] |
Definition at line 575 of file pacmod3_ros_msg_handler.cpp.
void Pacmod3TxRosMsgHandler::fillSteeringPIDRpt4 | ( | std::shared_ptr< Pacmod3TxMsg > & | parser_class, |
pacmod_msgs::SteeringPIDRpt4 & | new_msg, | ||
std::string | frame_id | ||
) | [private] |
Definition at line 588 of file pacmod3_ros_msg_handler.cpp.
void Pacmod3TxRosMsgHandler::fillSystemRptBool | ( | std::shared_ptr< Pacmod3TxMsg > & | parser_class, |
pacmod_msgs::SystemRptBool & | new_msg, | ||
std::string | frame_id | ||
) | [private] |
Definition at line 237 of file pacmod3_ros_msg_handler.cpp.
void Pacmod3TxRosMsgHandler::fillSystemRptFloat | ( | std::shared_ptr< Pacmod3TxMsg > & | parser_class, |
pacmod_msgs::SystemRptFloat & | new_msg, | ||
std::string | frame_id | ||
) | [private] |
Definition at line 277 of file pacmod3_ros_msg_handler.cpp.
void Pacmod3TxRosMsgHandler::fillSystemRptInt | ( | std::shared_ptr< Pacmod3TxMsg > & | parser_class, |
pacmod_msgs::SystemRptInt & | new_msg, | ||
std::string | frame_id | ||
) | [private] |
Definition at line 257 of file pacmod3_ros_msg_handler.cpp.
void Pacmod3TxRosMsgHandler::fillTurnAuxRpt | ( | std::shared_ptr< Pacmod3TxMsg > & | parser_class, |
pacmod_msgs::TurnAuxRpt & | new_msg, | ||
std::string | frame_id | ||
) | [private] |
Definition at line 599 of file pacmod3_ros_msg_handler.cpp.
void Pacmod3TxRosMsgHandler::fillVehicleDynamicsRpt | ( | std::shared_ptr< Pacmod3TxMsg > & | parser_class, |
pacmod_msgs::VehicleDynamicsRpt & | new_msg, | ||
std::string | frame_id | ||
) | [private] |
Definition at line 612 of file pacmod3_ros_msg_handler.cpp.
void Pacmod3TxRosMsgHandler::fillVehicleSpecificRpt1 | ( | std::shared_ptr< Pacmod3TxMsg > & | parser_class, |
pacmod_msgs::VehicleSpecificRpt1 & | new_msg, | ||
std::string | frame_id | ||
) | [private] |
Definition at line 623 of file pacmod3_ros_msg_handler.cpp.
void Pacmod3TxRosMsgHandler::fillVehicleSpeedRpt | ( | std::shared_ptr< Pacmod3TxMsg > & | parser_class, |
pacmod_msgs::VehicleSpeedRpt & | new_msg, | ||
std::string | frame_id | ||
) | [private] |
Definition at line 634 of file pacmod3_ros_msg_handler.cpp.
void Pacmod3TxRosMsgHandler::fillVinRpt | ( | std::shared_ptr< Pacmod3TxMsg > & | parser_class, |
pacmod_msgs::VinRpt & | new_msg, | ||
std::string | frame_id | ||
) | [private] |
Definition at line 647 of file pacmod3_ros_msg_handler.cpp.
void Pacmod3TxRosMsgHandler::fillWheelSpeedRpt | ( | std::shared_ptr< Pacmod3TxMsg > & | parser_class, |
pacmod_msgs::WheelSpeedRpt & | new_msg, | ||
std::string | frame_id | ||
) | [private] |
Definition at line 661 of file pacmod3_ros_msg_handler.cpp.
void Pacmod3TxRosMsgHandler::fillWiperAuxRpt | ( | std::shared_ptr< Pacmod3TxMsg > & | parser_class, |
pacmod_msgs::WiperAuxRpt & | new_msg, | ||
std::string | frame_id | ||
) | [private] |
Definition at line 674 of file pacmod3_ros_msg_handler.cpp.
void Pacmod3TxRosMsgHandler::fillYawRateRpt | ( | std::shared_ptr< Pacmod3TxMsg > & | parser_class, |
pacmod_msgs::YawRateRpt & | new_msg, | ||
std::string | frame_id | ||
) | [private] |
Definition at line 695 of file pacmod3_ros_msg_handler.cpp.