hz.cpp
Go to the documentation of this file.
1 /*********************************************************************
2  * Software License Agreement (BSD License)
3  *
4  * Copyright (c) 2017-2020, Dataspeed Inc.
5  * All rights reserved.
6  *
7  * Redistribution and use in source and binary forms, with or without
8  * modification, are permitted provided that the following conditions
9  * are met:
10  *
11  * * Redistributions of source code must retain the above copyright
12  * notice, this list of conditions and the following disclaimer.
13  * * Redistributions in binary form must reproduce the above
14  * copyright notice, this list of conditions and the following
15  * disclaimer in the documentation and/or other materials provided
16  * with the distribution.
17  * * Neither the name of Dataspeed Inc. nor the names of its
18  * contributors may be used to endorse or promote products derived
19  * from this software without specific prior written permission.
20  *
21  * THIS SOFTWARE IS PROVIDED BY THE COPYRIGHT HOLDERS AND CONTRIBUTORS
22  * "AS IS" AND ANY EXPRESS OR IMPLIED WARRANTIES, INCLUDING, BUT NOT
23  * LIMITED TO, THE IMPLIED WARRANTIES OF MERCHANTABILITY AND FITNESS
24  * FOR A PARTICULAR PURPOSE ARE DISCLAIMED. IN NO EVENT SHALL THE
25  * COPYRIGHT OWNER OR CONTRIBUTORS BE LIABLE FOR ANY DIRECT, INDIRECT,
26  * INCIDENTAL, SPECIAL, EXEMPLARY, OR CONSEQUENTIAL DAMAGES (INCLUDING,
27  * BUT NOT LIMITED TO, PROCUREMENT OF SUBSTITUTE GOODS OR SERVICES;
28  * LOSS OF USE, DATA, OR PROFITS; OR BUSINESS INTERRUPTION) HOWEVER
29  * CAUSED AND ON ANY THEORY OF LIABILITY, WHETHER IN CONTRACT, STRICT
30  * LIABILITY, OR TORT (INCLUDING NEGLIGENCE OR OTHERWISE) ARISING IN
31  * ANY WAY OUT OF THE USE OF THIS SOFTWARE, EVEN IF ADVISED OF THE
32  * POSSIBILITY OF SUCH DAMAGE.
33  *********************************************************************/
34 
35 // ROS and messages
36 #include <ros/ros.h>
37 #include <can_msgs/Frame.h>
38 
39 // CAN message definitions
41 using namespace dataspeed_pds_can;
42 
43 // Publisher
45 
46 can_msgs::Frame buildMsg(int unit_id, uint32_t can_id) {
47  can_msgs::Frame msg;
48  msg.header.stamp = ros::Time::now();
49  msg.dlc = 8;
50  msg.id = unit_id + can_id;
51  return msg;
52 }
53 
54 void timerCallback(const ros::TimerEvent&, int id)
55 {
56  ROS_ASSERT((0 <= id) && (id <= 3));
62 }
63 
64 int main(int argc, char **argv)
65 {
66  ros::init(argc, argv, "sim");
67  ros::NodeHandle nh;
68  ros::NodeHandle nh_priv("~");
69 
70  // Configurable period
71  double hz = 20; // 20 Hz
72  nh_priv.getParam("hz", hz);
73 
74  // Multiple units (optional)
75  int unit_id = 0;
76  nh_priv.getParam("unit_id", unit_id);
77  if (unit_id < 0) {
78  unit_id = 0;
79  } else if (unit_id > 3) {
80  unit_id = 3;
81  }
82 
83  // Setup Publishers
84  g_pub = nh.advertise<can_msgs::Frame>("can_tx", 100);
85 
86  // Setup Timers
87  std::vector<ros::Timer> timers;
88  for (int i = 0; i <= unit_id; i++) {
89  timers.push_back(nh.createTimer(ros::Duration(1.0 / hz), boost::bind(&timerCallback, _1, i)));
90  }
91 
92  // Handle callbacks until shutdown
93  ros::spin();
94 
95  return 0;
96 }
97 
buildMsg
can_msgs::Frame buildMsg(int unit_id, uint32_t can_id)
Definition: hz.cpp:46
ros::Publisher
ros::init
ROSCPP_DECL void init(const M_string &remappings, const std::string &name, uint32_t options=0)
ros::NodeHandle::getParam
bool getParam(const std::string &key, bool &b) const
ros.h
dataspeed_pds_can::ID_CURRENT3_MASTER
@ ID_CURRENT3_MASTER
Definition: dispatch.h:177
dataspeed_pds_can::ID_CURRENT1_MASTER
@ ID_CURRENT1_MASTER
Definition: dispatch.h:169
ros::Publisher::publish
void publish(const boost::shared_ptr< M > &message) const
ros::NodeHandle::advertise
Publisher advertise(AdvertiseOptions &ops)
dispatch.h
main
int main(int argc, char **argv)
Definition: hz.cpp:64
dataspeed_pds_can
Definition: dispatch.h:39
g_pub
ros::Publisher g_pub
Definition: hz.cpp:44
dataspeed_pds_can::ID_CURRENT2_MASTER
@ ID_CURRENT2_MASTER
Definition: dispatch.h:173
timerCallback
void timerCallback(const ros::TimerEvent &, int id)
Definition: hz.cpp:54
ros::TimerEvent
dataspeed_pds_can::ID_STATUS2_MASTER
@ ID_STATUS2_MASTER
Definition: dispatch.h:181
dataspeed_pds_can::ID_STATUS1_MASTER
@ ID_STATUS1_MASTER
Definition: dispatch.h:165
ros::spin
ROSCPP_DECL void spin()
ROS_ASSERT
#define ROS_ASSERT(cond)
ros::NodeHandle::createTimer
Timer createTimer(Duration period, const TimerCallback &callback, bool oneshot=false, bool autostart=true) const
ros::Duration
ros::NodeHandle
ros::Time::now
static Time now()


dataspeed_pds_can
Author(s): Kevin Hallenbeck , Eric Myllyoja , Michael Lohrer
autogenerated on Wed Mar 2 2022 00:11:44