Go to the documentation of this file.
35 #ifndef NEWEAGLE_PDU_H_
36 #define NEWEAGLE_PDU_H_
41 #include <can_msgs/Frame.h>
42 #include <pdu_msgs/FuseReport.h>
43 #include <pdu_msgs/RelayReport.h>
44 #include <pdu_msgs/RelayCommand.h>
45 #include <std_msgs/Empty.h>
46 #include <std_msgs/Bool.h>
47 #include <std_msgs/String.h>
78 void recvCAN(
const can_msgs::Frame::ConstPtr& msg);
79 void recvRelayCmd(
const pdu_msgs::RelayCommand::ConstPtr& msg);
@ RELAY_COMMAND_BASE_ADDR
uint32_t relayCommandAddr_
ros::Publisher fuse_report_pub_
ros::Subscriber sub_relay_cmd_
void recvRelayCmd(const pdu_msgs::RelayCommand::ConstPtr &msg)
pdu(ros::NodeHandle &node, ros::NodeHandle &priv_nh)
ros::Publisher relay_report_pub_
void recvCAN(const can_msgs::Frame::ConstPtr &msg)
uint32_t relayStatusAddr_
pdu
Author(s): Ryan Borchert
autogenerated on Sat Apr 9 2022 02:34:34