TwistControllerNode.h
Go to the documentation of this file.
1 /*********************************************************************
2  * Software License Agreement (BSD License)
3  *
4  * Copyright (c) 2015-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 TWISTCONTROLLERNODE_H_
36 #define TWISTCONTROLLERNODE_H_
37 
38 // ROS and messages
39 #include <ros/ros.h>
40 #include <std_msgs/Bool.h>
41 #include <sensor_msgs/Imu.h>
42 #include <dbw_mkz_msgs/ThrottleCmd.h>
43 #include <dbw_mkz_msgs/ThrottleReport.h>
44 #include <dbw_mkz_msgs/BrakeCmd.h>
45 #include <dbw_mkz_msgs/BrakeReport.h>
46 #include <dbw_mkz_msgs/SteeringCmd.h>
47 #include <dbw_mkz_msgs/SteeringReport.h>
48 #include <dbw_mkz_msgs/FuelLevelReport.h>
49 #include <dbw_mkz_msgs/TwistCmd.h>
50 #include <geometry_msgs/TwistStamped.h>
51 
52 // Debug message
53 #include <std_msgs/Float64.h>
54 
55 // Dynamic Reconfigure
56 #include <dynamic_reconfigure/server.h>
57 #include <dbw_mkz_twist_controller/ControllerConfig.h>
58 
59 // Controllers
60 #include "YawControl.h"
61 #include "PidControl.h"
62 #include "LowPass.h"
63 
64 namespace dbw_mkz_twist_controller {
65 
66 static const double GAS_DENSITY = 2.858; // kg/gal
67 
69 public:
71 private:
72  void reconfig(ControllerConfig& config, uint32_t level);
73  void controlCallback(const ros::TimerEvent& event);
74  void recvTwist(const geometry_msgs::Twist::ConstPtr& msg);
75  void recvTwist2(const dbw_mkz_msgs::TwistCmd::ConstPtr& msg);
76  void recvTwist3(const geometry_msgs::TwistStamped::ConstPtr& msg);
77  void recvSteeringReport(const dbw_mkz_msgs::SteeringReport::ConstPtr& msg);
78  void recvImu(const sensor_msgs::Imu::ConstPtr& msg);
79  void recvEnable(const std_msgs::Bool::ConstPtr& msg);
80  void recvFuel(const dbw_mkz_msgs::FuelLevelReport::ConstPtr& msg);
81 
95 
96  dbw_mkz_msgs::TwistCmd cmd_vel_;
97  geometry_msgs::Twist actual_;
99  dynamic_reconfigure::Server<ControllerConfig> srv_;
100 
106  ControllerConfig cfg_;
108 
109  // Parameters
112  double acker_track_;
114 
115  static double mphToMps(double mph) { return mph * 0.44704; }
116 };
117 
118 }
119 
120 #endif /* TWISTCONTROLLERNODE_H_ */
121 
static const double GAS_DENSITY
void recvEnable(const std_msgs::Bool::ConstPtr &msg)
void controlCallback(const ros::TimerEvent &event)
void recvSteeringReport(const dbw_mkz_msgs::SteeringReport::ConstPtr &msg)
void recvFuel(const dbw_mkz_msgs::FuelLevelReport::ConstPtr &msg)
void recvTwist(const geometry_msgs::Twist::ConstPtr &msg)
TwistControllerNode(ros::NodeHandle &n, ros::NodeHandle &pn)
void reconfig(ControllerConfig &config, uint32_t level)
dynamic_reconfigure::Server< ControllerConfig > srv_
void recvTwist2(const dbw_mkz_msgs::TwistCmd::ConstPtr &msg)
void recvImu(const sensor_msgs::Imu::ConstPtr &msg)
void recvTwist3(const geometry_msgs::TwistStamped::ConstPtr &msg)


dbw_mkz_twist_controller
Author(s): Micho Radovnikovich , Kevin Hallenbeck
autogenerated on Thu Nov 14 2019 03:46:10