Public Member Functions | Private Member Functions | Static Private Member Functions | Private Attributes | List of all members
dbw_mkz_twist_controller::TwistControllerNode Class Reference

#include <TwistControllerNode.h>

Public Member Functions

 TwistControllerNode (ros::NodeHandle &n, ros::NodeHandle &pn)
 

Private Member Functions

void controlCallback (const ros::TimerEvent &event)
 
void reconfig (ControllerConfig &config, uint32_t level)
 
void recvEnable (const std_msgs::Bool::ConstPtr &msg)
 
void recvFuel (const dbw_mkz_msgs::FuelLevelReport::ConstPtr &msg)
 
void recvImu (const sensor_msgs::Imu::ConstPtr &msg)
 
void recvSteeringReport (const dbw_mkz_msgs::SteeringReport::ConstPtr &msg)
 
void recvTwist (const geometry_msgs::Twist::ConstPtr &msg)
 
void recvTwist2 (const dbw_mkz_msgs::TwistCmd::ConstPtr &msg)
 
void recvTwist3 (const geometry_msgs::TwistStamped::ConstPtr &msg)
 

Static Private Member Functions

static double mphToMps (double mph)
 

Private Attributes

PidControl accel_pid_
 
double acker_track_
 
double acker_wheelbase_
 
geometry_msgs::Twist actual_
 
ControllerConfig cfg_
 
ros::Time cmd_stamp_
 
dbw_mkz_msgs::TwistCmd cmd_vel_
 
double control_period_
 
ros::Timer control_timer_
 
LowPass lpf_accel_
 
LowPass lpf_fuel_
 
ros::Publisher pub_accel_
 
ros::Publisher pub_brake_
 
ros::Publisher pub_req_accel_
 
ros::Publisher pub_steering_
 
ros::Publisher pub_throttle_
 
PidControl speed_pid_
 
dynamic_reconfigure::Server< ControllerConfig > srv_
 
double steering_ratio_
 
ros::Subscriber sub_enable_
 
ros::Subscriber sub_fuel_level_
 
ros::Subscriber sub_imu_
 
ros::Subscriber sub_steering_
 
ros::Subscriber sub_twist2_
 
ros::Subscriber sub_twist3_
 
ros::Subscriber sub_twist_
 
bool sys_enable_
 
YawControl yaw_control_
 

Detailed Description

Definition at line 68 of file TwistControllerNode.h.

Constructor & Destructor Documentation

dbw_mkz_twist_controller::TwistControllerNode::TwistControllerNode ( ros::NodeHandle n,
ros::NodeHandle pn 
)

Definition at line 39 of file TwistControllerNode.cpp.

Member Function Documentation

void dbw_mkz_twist_controller::TwistControllerNode::controlCallback ( const ros::TimerEvent event)
private

Definition at line 84 of file TwistControllerNode.cpp.

static double dbw_mkz_twist_controller::TwistControllerNode::mphToMps ( double  mph)
inlinestaticprivate

Definition at line 115 of file TwistControllerNode.h.

void dbw_mkz_twist_controller::TwistControllerNode::reconfig ( ControllerConfig &  config,
uint32_t  level 
)
private

Definition at line 154 of file TwistControllerNode.cpp.

void dbw_mkz_twist_controller::TwistControllerNode::recvEnable ( const std_msgs::Bool::ConstPtr &  msg)
private

Definition at line 210 of file TwistControllerNode.cpp.

void dbw_mkz_twist_controller::TwistControllerNode::recvFuel ( const dbw_mkz_msgs::FuelLevelReport::ConstPtr &  msg)
private

Definition at line 188 of file TwistControllerNode.cpp.

void dbw_mkz_twist_controller::TwistControllerNode::recvImu ( const sensor_msgs::Imu::ConstPtr &  msg)
private

Definition at line 205 of file TwistControllerNode.cpp.

void dbw_mkz_twist_controller::TwistControllerNode::recvSteeringReport ( const dbw_mkz_msgs::SteeringReport::ConstPtr &  msg)
private

Definition at line 193 of file TwistControllerNode.cpp.

void dbw_mkz_twist_controller::TwistControllerNode::recvTwist ( const geometry_msgs::Twist::ConstPtr &  msg)
private

Definition at line 166 of file TwistControllerNode.cpp.

void dbw_mkz_twist_controller::TwistControllerNode::recvTwist2 ( const dbw_mkz_msgs::TwistCmd::ConstPtr &  msg)
private

Definition at line 174 of file TwistControllerNode.cpp.

void dbw_mkz_twist_controller::TwistControllerNode::recvTwist3 ( const geometry_msgs::TwistStamped::ConstPtr &  msg)
private

Definition at line 180 of file TwistControllerNode.cpp.

Member Data Documentation

PidControl dbw_mkz_twist_controller::TwistControllerNode::accel_pid_
private

Definition at line 102 of file TwistControllerNode.h.

double dbw_mkz_twist_controller::TwistControllerNode::acker_track_
private

Definition at line 112 of file TwistControllerNode.h.

double dbw_mkz_twist_controller::TwistControllerNode::acker_wheelbase_
private

Definition at line 111 of file TwistControllerNode.h.

geometry_msgs::Twist dbw_mkz_twist_controller::TwistControllerNode::actual_
private

Definition at line 97 of file TwistControllerNode.h.

ControllerConfig dbw_mkz_twist_controller::TwistControllerNode::cfg_
private

Definition at line 106 of file TwistControllerNode.h.

ros::Time dbw_mkz_twist_controller::TwistControllerNode::cmd_stamp_
private

Definition at line 98 of file TwistControllerNode.h.

dbw_mkz_msgs::TwistCmd dbw_mkz_twist_controller::TwistControllerNode::cmd_vel_
private

Definition at line 96 of file TwistControllerNode.h.

double dbw_mkz_twist_controller::TwistControllerNode::control_period_
private

Definition at line 110 of file TwistControllerNode.h.

ros::Timer dbw_mkz_twist_controller::TwistControllerNode::control_timer_
private

Definition at line 94 of file TwistControllerNode.h.

LowPass dbw_mkz_twist_controller::TwistControllerNode::lpf_accel_
private

Definition at line 104 of file TwistControllerNode.h.

LowPass dbw_mkz_twist_controller::TwistControllerNode::lpf_fuel_
private

Definition at line 105 of file TwistControllerNode.h.

ros::Publisher dbw_mkz_twist_controller::TwistControllerNode::pub_accel_
private

Definition at line 85 of file TwistControllerNode.h.

ros::Publisher dbw_mkz_twist_controller::TwistControllerNode::pub_brake_
private

Definition at line 83 of file TwistControllerNode.h.

ros::Publisher dbw_mkz_twist_controller::TwistControllerNode::pub_req_accel_
private

Definition at line 86 of file TwistControllerNode.h.

ros::Publisher dbw_mkz_twist_controller::TwistControllerNode::pub_steering_
private

Definition at line 84 of file TwistControllerNode.h.

ros::Publisher dbw_mkz_twist_controller::TwistControllerNode::pub_throttle_
private

Definition at line 82 of file TwistControllerNode.h.

PidControl dbw_mkz_twist_controller::TwistControllerNode::speed_pid_
private

Definition at line 101 of file TwistControllerNode.h.

dynamic_reconfigure::Server<ControllerConfig> dbw_mkz_twist_controller::TwistControllerNode::srv_
private

Definition at line 99 of file TwistControllerNode.h.

double dbw_mkz_twist_controller::TwistControllerNode::steering_ratio_
private

Definition at line 113 of file TwistControllerNode.h.

ros::Subscriber dbw_mkz_twist_controller::TwistControllerNode::sub_enable_
private

Definition at line 89 of file TwistControllerNode.h.

ros::Subscriber dbw_mkz_twist_controller::TwistControllerNode::sub_fuel_level_
private

Definition at line 93 of file TwistControllerNode.h.

ros::Subscriber dbw_mkz_twist_controller::TwistControllerNode::sub_imu_
private

Definition at line 88 of file TwistControllerNode.h.

ros::Subscriber dbw_mkz_twist_controller::TwistControllerNode::sub_steering_
private

Definition at line 87 of file TwistControllerNode.h.

ros::Subscriber dbw_mkz_twist_controller::TwistControllerNode::sub_twist2_
private

Definition at line 91 of file TwistControllerNode.h.

ros::Subscriber dbw_mkz_twist_controller::TwistControllerNode::sub_twist3_
private

Definition at line 92 of file TwistControllerNode.h.

ros::Subscriber dbw_mkz_twist_controller::TwistControllerNode::sub_twist_
private

Definition at line 90 of file TwistControllerNode.h.

bool dbw_mkz_twist_controller::TwistControllerNode::sys_enable_
private

Definition at line 107 of file TwistControllerNode.h.

YawControl dbw_mkz_twist_controller::TwistControllerNode::yaw_control_
private

Definition at line 103 of file TwistControllerNode.h.


The documentation for this class was generated from the following files:


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