Public Member Functions | Public Attributes | List of all members
RbcarControllerClass Class Reference

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. More...
 
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. More...
 
void stopping ()
 Controller stopping. More...
 
void UpdateControl ()
 Controller update loop. More...
 
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 67 of file rbcar_robot_control.cpp.

Constructor & Destructor Documentation

RbcarControllerClass::RbcarControllerClass ( ros::NodeHandle  h)
inline

Public constructor.

Definition at line 188 of file rbcar_robot_control.cpp.

Member Function Documentation

void RbcarControllerClass::check_command_subscriber ( diagnostic_updater::DiagnosticStatusWrapper stat)
inline

Definition at line 510 of file rbcar_robot_control.cpp.

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

Definition at line 561 of file rbcar_robot_control.cpp.

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

Definition at line 572 of file rbcar_robot_control.cpp.

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

Definition at line 552 of file rbcar_robot_control.cpp.

void RbcarControllerClass::PublishOdometry ( )
inline

Definition at line 440 of file rbcar_robot_control.cpp.

double RbcarControllerClass::radnorm ( double  value)
inline

Definition at line 595 of file rbcar_robot_control.cpp.

double RbcarControllerClass::radnorm2 ( double  value)
inline

Definition at line 602 of file rbcar_robot_control.cpp.

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

Definition at line 588 of file rbcar_robot_control.cpp.

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

Definition at line 530 of file rbcar_robot_control.cpp.

bool RbcarControllerClass::spin ( )
inline

Definition at line 609 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 540 of file rbcar_robot_control.cpp.

int RbcarControllerClass::starting ( )
inline

Controller startup in realtime.

Definition at line 303 of file rbcar_robot_control.cpp.

void RbcarControllerClass::stopping ( )
inline

Controller stopping.

Definition at line 502 of file rbcar_robot_control.cpp.

void RbcarControllerClass::UpdateControl ( )
inline

Controller update loop.

Definition at line 322 of file rbcar_robot_control.cpp.

void RbcarControllerClass::UpdateOdometry ( )
inline

Definition at line 377 of file rbcar_robot_control.cpp.

Member Data Documentation

double RbcarControllerClass::alfa_ref_

Definition at line 148 of file rbcar_robot_control.cpp.

double RbcarControllerClass::ang_vel_x_

Definition at line 160 of file rbcar_robot_control.cpp.

double RbcarControllerClass::ang_vel_y_

Definition at line 161 of file rbcar_robot_control.cpp.

double RbcarControllerClass::ang_vel_z_

Definition at line 162 of file rbcar_robot_control.cpp.

double RbcarControllerClass::angularSpeedRads_

Definition at line 131 of file rbcar_robot_control.cpp.

ackermann_msgs::AckermannDriveStamped RbcarControllerClass::base_vel_msg_

Definition at line 144 of file rbcar_robot_control.cpp.

int RbcarControllerClass::blw_vel_

Definition at line 125 of file rbcar_robot_control.cpp.

std::string RbcarControllerClass::blw_vel_topic_

Definition at line 108 of file rbcar_robot_control.cpp.

int RbcarControllerClass::brw_vel_

Definition at line 125 of file rbcar_robot_control.cpp.

std::string RbcarControllerClass::brw_vel_topic_

Definition at line 107 of file rbcar_robot_control.cpp.

ros::Subscriber RbcarControllerClass::cmd_sub_

Definition at line 97 of file rbcar_robot_control.cpp.

diagnostic_updater::FunctionDiagnosticTask RbcarControllerClass::command_freq_

Definition at line 80 of file rbcar_robot_control.cpp.

double RbcarControllerClass::desired_freq_

Definition at line 73 of file rbcar_robot_control.cpp.

diagnostic_updater::Updater RbcarControllerClass::diagnostic_

Definition at line 76 of file rbcar_robot_control.cpp.

int RbcarControllerClass::flw_pos_

Definition at line 126 of file rbcar_robot_control.cpp.

std::string RbcarControllerClass::flw_pos_topic_

Definition at line 112 of file rbcar_robot_control.cpp.

int RbcarControllerClass::flw_vel_

Definition at line 125 of file rbcar_robot_control.cpp.

std::string RbcarControllerClass::flw_vel_topic_

Definition at line 106 of file rbcar_robot_control.cpp.

diagnostic_updater::FrequencyStatus RbcarControllerClass::freq_diag_

Definition at line 77 of file rbcar_robot_control.cpp.

int RbcarControllerClass::frw_pos_

Definition at line 126 of file rbcar_robot_control.cpp.

std::string RbcarControllerClass::frw_pos_topic_

Definition at line 111 of file rbcar_robot_control.cpp.

int RbcarControllerClass::frw_vel_

Definition at line 125 of file rbcar_robot_control.cpp.

std::string RbcarControllerClass::frw_vel_topic_

Definition at line 105 of file rbcar_robot_control.cpp.

ros::Subscriber RbcarControllerClass::imu_sub_

Definition at line 176 of file rbcar_robot_control.cpp.

std::string RbcarControllerClass::joint_back_left_wheel

Definition at line 117 of file rbcar_robot_control.cpp.

std::string RbcarControllerClass::joint_back_right_wheel

Definition at line 118 of file rbcar_robot_control.cpp.

std::string RbcarControllerClass::joint_front_left_steer

Definition at line 122 of file rbcar_robot_control.cpp.

std::string RbcarControllerClass::joint_front_left_wheel

Definition at line 116 of file rbcar_robot_control.cpp.

std::string RbcarControllerClass::joint_front_right_steer

Definition at line 121 of file rbcar_robot_control.cpp.

std::string RbcarControllerClass::joint_front_right_wheel

Definition at line 115 of file rbcar_robot_control.cpp.

sensor_msgs::JointState RbcarControllerClass::joint_state_

Definition at line 141 of file rbcar_robot_control.cpp.

ros::Subscriber RbcarControllerClass::joint_state_sub_

Definition at line 94 of file rbcar_robot_control.cpp.

ros::Time RbcarControllerClass::last_command_time_

Definition at line 79 of file rbcar_robot_control.cpp.

double RbcarControllerClass::lin_acc_x_

Definition at line 164 of file rbcar_robot_control.cpp.

double RbcarControllerClass::lin_acc_y_

Definition at line 165 of file rbcar_robot_control.cpp.

double RbcarControllerClass::lin_acc_z_

Definition at line 166 of file rbcar_robot_control.cpp.

double RbcarControllerClass::linearSpeedXMps_

Definition at line 129 of file rbcar_robot_control.cpp.

double RbcarControllerClass::linearSpeedYMps_

Definition at line 130 of file rbcar_robot_control.cpp.

ros::NodeHandle RbcarControllerClass::node_handle_

Definition at line 71 of file rbcar_robot_control.cpp.

tf::TransformBroadcaster RbcarControllerClass::odom_broadcaster

Definition at line 182 of file rbcar_robot_control.cpp.

ros::Publisher RbcarControllerClass::odom_pub_

Definition at line 179 of file rbcar_robot_control.cpp.

double RbcarControllerClass::orientation_w_

Definition at line 171 of file rbcar_robot_control.cpp.

double RbcarControllerClass::orientation_x_

Definition at line 168 of file rbcar_robot_control.cpp.

double RbcarControllerClass::orientation_y_

Definition at line 169 of file rbcar_robot_control.cpp.

double RbcarControllerClass::orientation_z_

Definition at line 170 of file rbcar_robot_control.cpp.

double RbcarControllerClass::pos_ref_pan_

Definition at line 149 of file rbcar_robot_control.cpp.

double RbcarControllerClass::pos_ref_tilt_

Definition at line 150 of file rbcar_robot_control.cpp.

ros::NodeHandle RbcarControllerClass::private_node_handle_

Definition at line 72 of file rbcar_robot_control.cpp.

bool RbcarControllerClass::publish_odom_tf_

Definition at line 174 of file rbcar_robot_control.cpp.

double RbcarControllerClass::rbcar_d_wheels_

Definition at line 157 of file rbcar_robot_control.cpp.

double RbcarControllerClass::rbcar_wheel_diameter_

Definition at line 156 of file rbcar_robot_control.cpp.

bool RbcarControllerClass::read_state_

Definition at line 153 of file rbcar_robot_control.cpp.

ros::Publisher RbcarControllerClass::ref_pos_flw_

Definition at line 90 of file rbcar_robot_control.cpp.

ros::Publisher RbcarControllerClass::ref_pos_frw_

Definition at line 91 of file rbcar_robot_control.cpp.

ros::Publisher RbcarControllerClass::ref_vel_blw_

Definition at line 88 of file rbcar_robot_control.cpp.

ros::Publisher RbcarControllerClass::ref_vel_brw_

Definition at line 89 of file rbcar_robot_control.cpp.

ros::Publisher RbcarControllerClass::ref_vel_flw_

Definition at line 86 of file rbcar_robot_control.cpp.

ros::Publisher RbcarControllerClass::ref_vel_frw_

Definition at line 87 of file rbcar_robot_control.cpp.

std::string RbcarControllerClass::robot_model_

Definition at line 83 of file rbcar_robot_control.cpp.

double RbcarControllerClass::robot_pose_pa_

Definition at line 136 of file rbcar_robot_control.cpp.

double RbcarControllerClass::robot_pose_px_

Definition at line 134 of file rbcar_robot_control.cpp.

double RbcarControllerClass::robot_pose_py_

Definition at line 135 of file rbcar_robot_control.cpp.

double RbcarControllerClass::robot_pose_vx_

Definition at line 137 of file rbcar_robot_control.cpp.

double RbcarControllerClass::robot_pose_vy_

Definition at line 138 of file rbcar_robot_control.cpp.

ros::ServiceServer RbcarControllerClass::srv_SetOdometry_

Definition at line 102 of file rbcar_robot_control.cpp.

diagnostic_updater::HeaderlessTopicDiagnostic* RbcarControllerClass::subs_command_freq

Definition at line 78 of file rbcar_robot_control.cpp.

double RbcarControllerClass::v_ref_

Definition at line 147 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 Mon Jun 10 2019 14:38:48