00001 /********************************************************************* 00002 * Software License Agreement (BSD License) 00003 * 00004 * Copyright (c) 2015-2018, Dataspeed Inc. 00005 * All rights reserved. 00006 * 00007 * Redistribution and use in source and binary forms, with or without 00008 * modification, are permitted provided that the following conditions 00009 * are met: 00010 * 00011 * * Redistributions of source code must retain the above copyright 00012 * notice, this list of conditions and the following disclaimer. 00013 * * Redistributions in binary form must reproduce the above 00014 * copyright notice, this list of conditions and the following 00015 * disclaimer in the documentation and/or other materials provided 00016 * with the distribution. 00017 * * Neither the name of Dataspeed Inc. nor the names of its 00018 * contributors may be used to endorse or promote products derived 00019 * from this software without specific prior written permission. 00020 * 00021 * THIS SOFTWARE IS PROVIDED BY THE COPYRIGHT HOLDERS AND CONTRIBUTORS 00022 * "AS IS" AND ANY EXPRESS OR IMPLIED WARRANTIES, INCLUDING, BUT NOT 00023 * LIMITED TO, THE IMPLIED WARRANTIES OF MERCHANTABILITY AND FITNESS 00024 * FOR A PARTICULAR PURPOSE ARE DISCLAIMED. IN NO EVENT SHALL THE 00025 * COPYRIGHT OWNER OR CONTRIBUTORS BE LIABLE FOR ANY DIRECT, INDIRECT, 00026 * INCIDENTAL, SPECIAL, EXEMPLARY, OR CONSEQUENTIAL DAMAGES (INCLUDING, 00027 * BUT NOT LIMITED TO, PROCUREMENT OF SUBSTITUTE GOODS OR SERVICES; 00028 * LOSS OF USE, DATA, OR PROFITS; OR BUSINESS INTERRUPTION) HOWEVER 00029 * CAUSED AND ON ANY THEORY OF LIABILITY, WHETHER IN CONTRACT, STRICT 00030 * LIABILITY, OR TORT (INCLUDING NEGLIGENCE OR OTHERWISE) ARISING IN 00031 * ANY WAY OUT OF THE USE OF THIS SOFTWARE, EVEN IF ADVISED OF THE 00032 * POSSIBILITY OF SUCH DAMAGE. 00033 *********************************************************************/ 00034 00035 #ifndef TWISTCONTROLLERNODE_H_ 00036 #define TWISTCONTROLLERNODE_H_ 00037 00038 // ROS and messages 00039 #include <ros/ros.h> 00040 #include <std_msgs/Bool.h> 00041 #include <sensor_msgs/Imu.h> 00042 #include <dbw_mkz_msgs/ThrottleCmd.h> 00043 #include <dbw_mkz_msgs/ThrottleReport.h> 00044 #include <dbw_mkz_msgs/BrakeCmd.h> 00045 #include <dbw_mkz_msgs/BrakeReport.h> 00046 #include <dbw_mkz_msgs/SteeringCmd.h> 00047 #include <dbw_mkz_msgs/SteeringReport.h> 00048 #include <dbw_mkz_msgs/FuelLevelReport.h> 00049 #include <dbw_mkz_msgs/TwistCmd.h> 00050 #include <geometry_msgs/TwistStamped.h> 00051 00052 // Debug message 00053 #include <std_msgs/Float64.h> 00054 00055 // Dynamic Reconfigure 00056 #include <dynamic_reconfigure/server.h> 00057 #include <dbw_mkz_twist_controller/ControllerConfig.h> 00058 00059 // Controllers 00060 #include "YawControl.h" 00061 #include "PidControl.h" 00062 #include "LowPass.h" 00063 00064 namespace dbw_mkz_twist_controller { 00065 00066 static const double GAS_DENSITY = 2.858; // kg/gal 00067 00068 class TwistControllerNode{ 00069 public: 00070 TwistControllerNode(ros::NodeHandle &n, ros::NodeHandle &pn); 00071 private: 00072 void reconfig(ControllerConfig& config, uint32_t level); 00073 void controlCallback(const ros::TimerEvent& event); 00074 void recvTwist(const geometry_msgs::Twist::ConstPtr& msg); 00075 void recvTwist2(const dbw_mkz_msgs::TwistCmd::ConstPtr& msg); 00076 void recvTwist3(const geometry_msgs::TwistStamped::ConstPtr& msg); 00077 void recvSteeringReport(const dbw_mkz_msgs::SteeringReport::ConstPtr& msg); 00078 void recvImu(const sensor_msgs::Imu::ConstPtr& msg); 00079 void recvEnable(const std_msgs::Bool::ConstPtr& msg); 00080 void recvFuel(const dbw_mkz_msgs::FuelLevelReport::ConstPtr& msg); 00081 00082 ros::Publisher pub_throttle_; 00083 ros::Publisher pub_brake_; 00084 ros::Publisher pub_steering_; 00085 ros::Publisher pub_accel_; 00086 ros::Publisher pub_req_accel_; 00087 ros::Subscriber sub_steering_; 00088 ros::Subscriber sub_imu_; 00089 ros::Subscriber sub_enable_; 00090 ros::Subscriber sub_twist_; 00091 ros::Subscriber sub_twist2_; 00092 ros::Subscriber sub_twist3_; 00093 ros::Subscriber sub_fuel_level_; 00094 ros::Timer control_timer_; 00095 00096 dbw_mkz_msgs::TwistCmd cmd_vel_; 00097 geometry_msgs::Twist actual_; 00098 ros::Time cmd_stamp_; 00099 dynamic_reconfigure::Server<ControllerConfig> srv_; 00100 00101 PidControl speed_pid_; 00102 PidControl accel_pid_; 00103 YawControl yaw_control_; 00104 LowPass lpf_accel_; 00105 LowPass lpf_fuel_; 00106 ControllerConfig cfg_; 00107 bool sys_enable_; 00108 00109 // Parameters 00110 double control_period_; 00111 double acker_wheelbase_; 00112 double acker_track_; 00113 double steering_ratio_; 00114 00115 static double mphToMps(double mph) { return mph * 0.44704; } 00116 }; 00117 00118 } 00119 00120 #endif /* TWISTCONTROLLERNODE_H_ */ 00121