37 #include <can_msgs/Frame.h>    46 can_msgs::Frame 
buildMsg(
int unit_id, uint32_t can_id) {
    50   msg.id = unit_id + can_id;
    64 int main(
int argc, 
char **argv)
    76   nh_priv.
getParam(
"unit_id", unit_id);
    79   } 
else if (unit_id > 3) {
    84   g_pub = nh.
advertise<can_msgs::Frame>(
"can_tx", 100);
    87   std::vector<ros::Timer> timers;
    88   for (
int i = 0; i <= unit_id; i++) {
 
void publish(const boost::shared_ptr< M > &message) const 
 
ROSCPP_DECL void init(int &argc, char **argv, const std::string &name, uint32_t options=0)
 
int main(int argc, char **argv)
 
ROSCPP_DECL void spin(Spinner &spinner)
 
can_msgs::Frame buildMsg(int unit_id, uint32_t can_id)
 
Timer createTimer(Rate r, Handler h, Obj o, bool oneshot=false, bool autostart=true) const 
 
Publisher advertise(const std::string &topic, uint32_t queue_size, bool latch=false)
 
bool getParam(const std::string &key, std::string &s) const 
 
void timerCallback(const ros::TimerEvent &, int id)