Public Member Functions | Public Attributes
RbcarControllerClass Class Reference

List of all members.

Public Member Functions

void check_command_subscriber (diagnostic_updater::DiagnosticStatusWrapper &stat)
void commandCallback (const ackermann_msgs::AckermannDriveStamped::ConstPtr &msg)
void imuCallback (const sensor_msgs::Imu &imu_msg)
void jointStateCallback (const sensor_msgs::JointStateConstPtr &msg)
void PublishOdometry ()
double radnorm (double value)
double radnorm2 (double value)
 RbcarControllerClass (ros::NodeHandle h)
 Public constructor.
double saturation (double u, double min, double max)
void setCommand (const ackermann_msgs::AckermannDriveStamped &msg)
bool spin ()
bool srvCallback_SetOdometry (robotnik_msgs::set_odometry::Request &request, robotnik_msgs::set_odometry::Response &response)
int starting ()
 Controller startup in realtime.
void stopping ()
 Controller stopping.
void UpdateControl ()
 Controller update loop.
void UpdateOdometry ()

Public Attributes

double alfa_ref_
double ang_vel_x_
double ang_vel_y_
double ang_vel_z_
double angularSpeedRads_
ackermann_msgs::AckermannDriveStamped base_vel_msg_
int blw_vel_
std::string blw_vel_topic_
int brw_vel_
std::string brw_vel_topic_
ros::Subscriber cmd_sub_
diagnostic_updater::FunctionDiagnosticTask command_freq_
double desired_freq_
diagnostic_updater::Updater diagnostic_
int flw_pos_
std::string flw_pos_topic_
int flw_vel_
std::string flw_vel_topic_
diagnostic_updater::FrequencyStatus freq_diag_
int frw_pos_
std::string frw_pos_topic_
int frw_vel_
std::string frw_vel_topic_
ros::Subscriber imu_sub_
std::string joint_back_left_wheel
std::string joint_back_right_wheel
std::string joint_front_left_steer
std::string joint_front_left_wheel
std::string joint_front_right_steer
std::string joint_front_right_wheel
sensor_msgs::JointState joint_state_
ros::Subscriber joint_state_sub_
ros::Time last_command_time_
double lin_acc_x_
double lin_acc_y_
double lin_acc_z_
double linearSpeedXMps_
double linearSpeedYMps_
ros::NodeHandle node_handle_
tf::TransformBroadcaster odom_broadcaster
ros::Publisher odom_pub_
double orientation_w_
double orientation_x_
double orientation_y_
double orientation_z_
double pos_ref_pan_
double pos_ref_tilt_
ros::NodeHandle private_node_handle_
bool publish_odom_tf_
double rbcar_d_wheels_
double rbcar_wheel_diameter_
bool read_state_
ros::Publisher ref_pos_flw_
ros::Publisher ref_pos_frw_
ros::Publisher ref_vel_blw_
ros::Publisher ref_vel_brw_
ros::Publisher ref_vel_flw_
ros::Publisher ref_vel_frw_
std::string robot_model_
double robot_pose_pa_
double robot_pose_px_
double robot_pose_py_
double robot_pose_vx_
double robot_pose_vy_
ros::ServiceServer srv_SetOdometry_
diagnostic_updater::HeaderlessTopicDiagnosticsubs_command_freq
double v_ref_

Detailed Description

Definition at line 66 of file rbcar_robot_control.cpp.


Constructor & Destructor Documentation

Public constructor.

Definition at line 187 of file rbcar_robot_control.cpp.


Member Function Documentation

Definition at line 500 of file rbcar_robot_control.cpp.

void RbcarControllerClass::commandCallback ( const ackermann_msgs::AckermannDriveStamped::ConstPtr &  msg) [inline]

Definition at line 551 of file rbcar_robot_control.cpp.

void RbcarControllerClass::imuCallback ( const sensor_msgs::Imu &  imu_msg) [inline]

Definition at line 562 of file rbcar_robot_control.cpp.

void RbcarControllerClass::jointStateCallback ( const sensor_msgs::JointStateConstPtr &  msg) [inline]

Definition at line 542 of file rbcar_robot_control.cpp.

Definition at line 430 of file rbcar_robot_control.cpp.

double RbcarControllerClass::radnorm ( double  value) [inline]

Definition at line 585 of file rbcar_robot_control.cpp.

double RbcarControllerClass::radnorm2 ( double  value) [inline]

Definition at line 592 of file rbcar_robot_control.cpp.

double RbcarControllerClass::saturation ( double  u,
double  min,
double  max 
) [inline]

Definition at line 578 of file rbcar_robot_control.cpp.

void RbcarControllerClass::setCommand ( const ackermann_msgs::AckermannDriveStamped &  msg) [inline]

Definition at line 520 of file rbcar_robot_control.cpp.

bool RbcarControllerClass::spin ( ) [inline]

Definition at line 599 of file rbcar_robot_control.cpp.

bool RbcarControllerClass::srvCallback_SetOdometry ( robotnik_msgs::set_odometry::Request &  request,
robotnik_msgs::set_odometry::Response &  response 
) [inline]

Definition at line 530 of file rbcar_robot_control.cpp.

Controller startup in realtime.

Definition at line 302 of file rbcar_robot_control.cpp.

void RbcarControllerClass::stopping ( ) [inline]

Controller stopping.

Definition at line 492 of file rbcar_robot_control.cpp.

Controller update loop.

Definition at line 321 of file rbcar_robot_control.cpp.

Definition at line 376 of file rbcar_robot_control.cpp.


Member Data Documentation

Definition at line 147 of file rbcar_robot_control.cpp.

Definition at line 159 of file rbcar_robot_control.cpp.

Definition at line 160 of file rbcar_robot_control.cpp.

Definition at line 161 of file rbcar_robot_control.cpp.

Definition at line 130 of file rbcar_robot_control.cpp.

ackermann_msgs::AckermannDriveStamped RbcarControllerClass::base_vel_msg_

Definition at line 143 of file rbcar_robot_control.cpp.

Definition at line 124 of file rbcar_robot_control.cpp.

Definition at line 107 of file rbcar_robot_control.cpp.

Definition at line 124 of file rbcar_robot_control.cpp.

Definition at line 106 of file rbcar_robot_control.cpp.

Definition at line 96 of file rbcar_robot_control.cpp.

Definition at line 79 of file rbcar_robot_control.cpp.

Definition at line 72 of file rbcar_robot_control.cpp.

Definition at line 75 of file rbcar_robot_control.cpp.

Definition at line 125 of file rbcar_robot_control.cpp.

Definition at line 111 of file rbcar_robot_control.cpp.

Definition at line 124 of file rbcar_robot_control.cpp.

Definition at line 105 of file rbcar_robot_control.cpp.

Definition at line 76 of file rbcar_robot_control.cpp.

Definition at line 125 of file rbcar_robot_control.cpp.

Definition at line 110 of file rbcar_robot_control.cpp.

Definition at line 124 of file rbcar_robot_control.cpp.

Definition at line 104 of file rbcar_robot_control.cpp.

Definition at line 175 of file rbcar_robot_control.cpp.

Definition at line 116 of file rbcar_robot_control.cpp.

Definition at line 117 of file rbcar_robot_control.cpp.

Definition at line 121 of file rbcar_robot_control.cpp.

Definition at line 115 of file rbcar_robot_control.cpp.

Definition at line 120 of file rbcar_robot_control.cpp.

Definition at line 114 of file rbcar_robot_control.cpp.

sensor_msgs::JointState RbcarControllerClass::joint_state_

Definition at line 140 of file rbcar_robot_control.cpp.

Definition at line 93 of file rbcar_robot_control.cpp.

Definition at line 78 of file rbcar_robot_control.cpp.

Definition at line 163 of file rbcar_robot_control.cpp.

Definition at line 164 of file rbcar_robot_control.cpp.

Definition at line 165 of file rbcar_robot_control.cpp.

Definition at line 128 of file rbcar_robot_control.cpp.

Definition at line 129 of file rbcar_robot_control.cpp.

Definition at line 70 of file rbcar_robot_control.cpp.

Definition at line 181 of file rbcar_robot_control.cpp.

Definition at line 178 of file rbcar_robot_control.cpp.

Definition at line 170 of file rbcar_robot_control.cpp.

Definition at line 167 of file rbcar_robot_control.cpp.

Definition at line 168 of file rbcar_robot_control.cpp.

Definition at line 169 of file rbcar_robot_control.cpp.

Definition at line 148 of file rbcar_robot_control.cpp.

Definition at line 149 of file rbcar_robot_control.cpp.

Definition at line 71 of file rbcar_robot_control.cpp.

Definition at line 173 of file rbcar_robot_control.cpp.

Definition at line 156 of file rbcar_robot_control.cpp.

Definition at line 155 of file rbcar_robot_control.cpp.

Definition at line 152 of file rbcar_robot_control.cpp.

Definition at line 89 of file rbcar_robot_control.cpp.

Definition at line 90 of file rbcar_robot_control.cpp.

Definition at line 87 of file rbcar_robot_control.cpp.

Definition at line 88 of file rbcar_robot_control.cpp.

Definition at line 85 of file rbcar_robot_control.cpp.

Definition at line 86 of file rbcar_robot_control.cpp.

Definition at line 82 of file rbcar_robot_control.cpp.

Definition at line 135 of file rbcar_robot_control.cpp.

Definition at line 133 of file rbcar_robot_control.cpp.

Definition at line 134 of file rbcar_robot_control.cpp.

Definition at line 136 of file rbcar_robot_control.cpp.

Definition at line 137 of file rbcar_robot_control.cpp.

Definition at line 101 of file rbcar_robot_control.cpp.

Definition at line 77 of file rbcar_robot_control.cpp.

Definition at line 146 of file rbcar_robot_control.cpp.


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


rbcar_robot_control
Author(s): Roberto Guzman
autogenerated on Thu Jun 6 2019 19:55:50