UlcNode.h
Go to the documentation of this file.
1 /*********************************************************************
2  * Software License Agreement (BSD License)
3  *
4  * Copyright (c) 2018, 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 #ifndef ULCNODE_H
36 #define ULCNODE_H
37 
38 #include <ros/ros.h>
39 #include <std_msgs/Bool.h>
40 #include <geometry_msgs/TwistStamped.h>
41 #include <can_msgs/Frame.h>
42 #include <dataspeed_ulc_msgs/UlcCmd.h>
43 #include <dataspeed_ulc_msgs/UlcReport.h>
44 
46 
47 namespace dataspeed_ulc_can
48 {
49 
50 class UlcNode
51 {
52 public:
54 private:
55 
56  void recvCan(const can_msgs::FrameConstPtr& msg);
57  void recvUlcCmd(const dataspeed_ulc_msgs::UlcCmdConstPtr& msg);
58  void recvTwistCmd(const geometry_msgs::Twist& msg);
59  void recvTwist(const geometry_msgs::TwistConstPtr& msg);
60  void recvTwistStamped(const geometry_msgs::TwistStampedConstPtr& msg);
61  void recvEnable(const std_msgs::BoolConstPtr& msg);
62  void configTimerCb(const ros::TimerEvent& event);
63  void sendCmdMsg(bool cfg);
64  void sendCfgMsg();
65 
74 
75  dataspeed_ulc_msgs::UlcCmd ulc_cmd_;
77  bool enable_;
79 
80  // Firmware Versions
82 };
83 
84 }
85 
86 #endif // ULCNODE_H
ros::Subscriber sub_twist_stamped_
Definition: UlcNode.h:68
void recvEnable(const std_msgs::BoolConstPtr &msg)
Definition: UlcNode.cpp:151
void recvTwistCmd(const geometry_msgs::Twist &msg)
Definition: UlcNode.cpp:176
void sendCmdMsg(bool cfg)
Definition: UlcNode.cpp:262
void recvCan(const can_msgs::FrameConstPtr &msg)
Definition: UlcNode.cpp:212
ros::NodeHandle * n
ros::NodeHandle * pn
ros::Subscriber sub_cmd_
Definition: UlcNode.h:66
dataspeed_ulc_msgs::UlcCmd ulc_cmd_
Definition: UlcNode.h:75
void recvTwist(const geometry_msgs::TwistConstPtr &msg)
Definition: UlcNode.cpp:202
UlcNode(ros::NodeHandle &n, ros::NodeHandle &pn)
Definition: UlcNode.cpp:130
ros::Timer config_timer_
Definition: UlcNode.h:73
void recvTwistStamped(const geometry_msgs::TwistStampedConstPtr &msg)
Definition: UlcNode.cpp:207
ros::Subscriber sub_can_
Definition: UlcNode.h:69
ros::Subscriber sub_enable_
Definition: UlcNode.h:70
ros::Publisher pub_can_
Definition: UlcNode.h:72
PlatformMap firmware_
Definition: UlcNode.h:81
ros::Publisher pub_report_
Definition: UlcNode.h:71
ros::Subscriber sub_twist_
Definition: UlcNode.h:67
void recvUlcCmd(const dataspeed_ulc_msgs::UlcCmdConstPtr &msg)
Definition: UlcNode.cpp:156
void configTimerCb(const ros::TimerEvent &event)
Definition: UlcNode.cpp:353


dataspeed_ulc_can
Author(s): Micho Radovnikovich
autogenerated on Fri Dec 2 2022 03:20:37