35 #ifndef TWISTCONTROLLERNODE_H_ 36 #define TWISTCONTROLLERNODE_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> 53 #include <std_msgs/Float64.h> 56 #include <dynamic_reconfigure/server.h> 57 #include <dbw_mkz_twist_controller/ControllerConfig.h> 72 void reconfig(ControllerConfig& config, uint32_t level);
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);
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);
99 dynamic_reconfigure::Server<ControllerConfig>
srv_;
115 static double mphToMps(
double mph) {
return mph * 0.44704; }
static const double GAS_DENSITY
void recvEnable(const std_msgs::Bool::ConstPtr &msg)
void controlCallback(const ros::TimerEvent &event)
ros::Publisher pub_brake_
void recvSteeringReport(const dbw_mkz_msgs::SteeringReport::ConstPtr &msg)
ros::Subscriber sub_twist2_
void recvFuel(const dbw_mkz_msgs::FuelLevelReport::ConstPtr &msg)
ros::Timer control_timer_
ros::Subscriber sub_twist3_
void recvTwist(const geometry_msgs::Twist::ConstPtr &msg)
ros::Subscriber sub_enable_
ros::Publisher pub_throttle_
ros::Publisher pub_req_accel_
TwistControllerNode(ros::NodeHandle &n, ros::NodeHandle &pn)
void reconfig(ControllerConfig &config, uint32_t level)
dbw_mkz_msgs::TwistCmd cmd_vel_
geometry_msgs::Twist actual_
dynamic_reconfigure::Server< ControllerConfig > srv_
void recvTwist2(const dbw_mkz_msgs::TwistCmd::ConstPtr &msg)
ros::Publisher pub_accel_
void recvImu(const sensor_msgs::Imu::ConstPtr &msg)
ros::Subscriber sub_fuel_level_
ros::Publisher pub_steering_
ros::Subscriber sub_steering_
ros::Subscriber sub_twist_
static double mphToMps(double mph)
void recvTwist3(const geometry_msgs::TwistStamped::ConstPtr &msg)