Public Member Functions | Static Public Member Functions | Public Attributes | List of all members
AGVSControllerClass Class Reference

Public Member Functions

 AGVSControllerClass (ros::NodeHandle h)
 Public constructor. More...
 
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 saturation (double u, double min, double max)
 
void SetElevatorPosition (double val)
 
bool spin ()
 
bool srvCallback_LowerElevator (std_srvs::Empty::Request &request, std_srvs::Empty::Response &response)
 
bool srvCallback_RaiseElevator (std_srvs::Empty::Request &request, std_srvs::Empty::Response &response)
 
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 ()
 
void UpdateOdometry ()
 Updates the values of the odometry Ackerman's odometry calculation (using motor speed and position of the motor direction) More...
 

Static Public Member Functions

static void radnorm (double *radians)
 Normalize in rad. More...
 
static double radnorm2 (double value)
 

Public Attributes

double a_ref_
 
double agvs_dist_to_center_
 
double agvs_wheel_diameter_
 
double ang_vel_x_
 
double ang_vel_y_
 
double ang_vel_z_
 
double angularSpeedRads_
 
ackermann_msgs::AckermannDriveStamped base_vel_msg_
 
int bwd_pos_
 
std::string bwd_pos_topic_
 
int bwd_vel_
 
std::string bwd_vel_topic_
 
ros::Subscriber cmd_sub_
 
diagnostic_updater::FunctionDiagnosticTask command_freq_
 
double desired_freq_
 
diagnostic_updater::Updater diagnostic_
 
std::string elevator_pos_topic_
 
diagnostic_updater::FrequencyStatus freq_diag_
 
int fwd_pos_
 
std::string fwd_pos_topic_
 
int fwd_vel_
 
std::string fwd_vel_topic_
 
ros::Subscriber imu_sub_
 
std::string imu_topic_
 
std::string joint_back_motor_wheel
 
std::string joint_back_wheel
 
std::string joint_front_motor_wheel
 
std::string joint_front_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_diff_w_
 
double orientation_diff_x_
 
double orientation_diff_y_
 
double orientation_diff_z_
 
ros::NodeHandle private_node_handle_
 
bool publish_odom_tf_
 
bool read_state_
 
ros::Publisher ref_pos_bwd_
 
ros::Publisher ref_pos_elevator_
 
ros::Publisher ref_pos_fwd_
 
ros::Publisher ref_vel_bwd_
 
ros::Publisher ref_vel_fwd_
 
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_GetMode_
 
ros::ServiceServer srv_LowerElevator_
 
ros::ServiceServer srv_RaiseElevator_
 
ros::ServiceServer srv_SetMode_
 
ros::ServiceServer srv_SetOdometry_
 
diagnostic_updater::HeaderlessTopicDiagnosticsubs_command_freq
 
double v_mps_
 
double v_ref_
 

Detailed Description

Definition at line 68 of file agvs_robot_control.cpp.

Constructor & Destructor Documentation

AGVSControllerClass::AGVSControllerClass ( ros::NodeHandle  h)
inline

Public constructor.

Definition at line 190 of file agvs_robot_control.cpp.

Member Function Documentation

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

Definition at line 501 of file agvs_robot_control.cpp.

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

Definition at line 554 of file agvs_robot_control.cpp.

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

Definition at line 567 of file agvs_robot_control.cpp.

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

Definition at line 547 of file agvs_robot_control.cpp.

void AGVSControllerClass::PublishOdometry ( )
inline

Definition at line 381 of file agvs_robot_control.cpp.

static void AGVSControllerClass::radnorm ( double *  radians)
inlinestatic

Normalize in rad.

Definition at line 593 of file agvs_robot_control.cpp.

static double AGVSControllerClass::radnorm2 ( double  value)
inlinestatic

Definition at line 603 of file agvs_robot_control.cpp.

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

Definition at line 583 of file agvs_robot_control.cpp.

void AGVSControllerClass::SetElevatorPosition ( double  val)
inline

Definition at line 484 of file agvs_robot_control.cpp.

bool AGVSControllerClass::spin ( )
inline

Definition at line 610 of file agvs_robot_control.cpp.

bool AGVSControllerClass::srvCallback_LowerElevator ( std_srvs::Empty::Request &  request,
std_srvs::Empty::Response &  response 
)
inline

Definition at line 538 of file agvs_robot_control.cpp.

bool AGVSControllerClass::srvCallback_RaiseElevator ( std_srvs::Empty::Request &  request,
std_srvs::Empty::Response &  response 
)
inline

Definition at line 529 of file agvs_robot_control.cpp.

bool AGVSControllerClass::srvCallback_SetOdometry ( robotnik_msgs::set_odometry::Request &  request,
robotnik_msgs::set_odometry::Response &  response 
)
inline

Definition at line 517 of file agvs_robot_control.cpp.

int AGVSControllerClass::starting ( )
inline

Controller startup in realtime.

Definition at line 305 of file agvs_robot_control.cpp.

void AGVSControllerClass::stopping ( )
inline

Controller stopping.

Definition at line 494 of file agvs_robot_control.cpp.

void AGVSControllerClass::UpdateControl ( )
inline

Definition at line 447 of file agvs_robot_control.cpp.

void AGVSControllerClass::UpdateOdometry ( )
inline

Updates the values of the odometry Ackerman's odometry calculation (using motor speed and position of the motor direction)

Definition at line 330 of file agvs_robot_control.cpp.

Member Data Documentation

double AGVSControllerClass::a_ref_

Definition at line 150 of file agvs_robot_control.cpp.

double AGVSControllerClass::agvs_dist_to_center_

Definition at line 159 of file agvs_robot_control.cpp.

double AGVSControllerClass::agvs_wheel_diameter_

Definition at line 158 of file agvs_robot_control.cpp.

double AGVSControllerClass::ang_vel_x_

Definition at line 162 of file agvs_robot_control.cpp.

double AGVSControllerClass::ang_vel_y_

Definition at line 163 of file agvs_robot_control.cpp.

double AGVSControllerClass::ang_vel_z_

Definition at line 164 of file agvs_robot_control.cpp.

double AGVSControllerClass::angularSpeedRads_

Definition at line 132 of file agvs_robot_control.cpp.

ackermann_msgs::AckermannDriveStamped AGVSControllerClass::base_vel_msg_

Definition at line 146 of file agvs_robot_control.cpp.

int AGVSControllerClass::bwd_pos_

Definition at line 127 of file agvs_robot_control.cpp.

std::string AGVSControllerClass::bwd_pos_topic_

Definition at line 116 of file agvs_robot_control.cpp.

int AGVSControllerClass::bwd_vel_

Definition at line 126 of file agvs_robot_control.cpp.

std::string AGVSControllerClass::bwd_vel_topic_

Definition at line 108 of file agvs_robot_control.cpp.

ros::Subscriber AGVSControllerClass::cmd_sub_

Definition at line 97 of file agvs_robot_control.cpp.

diagnostic_updater::FunctionDiagnosticTask AGVSControllerClass::command_freq_

Definition at line 81 of file agvs_robot_control.cpp.

double AGVSControllerClass::desired_freq_

Definition at line 74 of file agvs_robot_control.cpp.

diagnostic_updater::Updater AGVSControllerClass::diagnostic_

Definition at line 77 of file agvs_robot_control.cpp.

std::string AGVSControllerClass::elevator_pos_topic_

Definition at line 117 of file agvs_robot_control.cpp.

diagnostic_updater::FrequencyStatus AGVSControllerClass::freq_diag_

Definition at line 78 of file agvs_robot_control.cpp.

int AGVSControllerClass::fwd_pos_

Definition at line 127 of file agvs_robot_control.cpp.

std::string AGVSControllerClass::fwd_pos_topic_

Definition at line 115 of file agvs_robot_control.cpp.

int AGVSControllerClass::fwd_vel_

Definition at line 126 of file agvs_robot_control.cpp.

std::string AGVSControllerClass::fwd_vel_topic_

Definition at line 107 of file agvs_robot_control.cpp.

ros::Subscriber AGVSControllerClass::imu_sub_

Definition at line 178 of file agvs_robot_control.cpp.

std::string AGVSControllerClass::imu_topic_

Definition at line 119 of file agvs_robot_control.cpp.

std::string AGVSControllerClass::joint_back_motor_wheel

Definition at line 123 of file agvs_robot_control.cpp.

std::string AGVSControllerClass::joint_back_wheel

Definition at line 112 of file agvs_robot_control.cpp.

std::string AGVSControllerClass::joint_front_motor_wheel

Definition at line 122 of file agvs_robot_control.cpp.

std::string AGVSControllerClass::joint_front_wheel

Definition at line 111 of file agvs_robot_control.cpp.

sensor_msgs::JointState AGVSControllerClass::joint_state_

Definition at line 142 of file agvs_robot_control.cpp.

ros::Subscriber AGVSControllerClass::joint_state_sub_

Definition at line 94 of file agvs_robot_control.cpp.

ros::Time AGVSControllerClass::last_command_time_

Definition at line 80 of file agvs_robot_control.cpp.

double AGVSControllerClass::lin_acc_x_

Definition at line 166 of file agvs_robot_control.cpp.

double AGVSControllerClass::lin_acc_y_

Definition at line 167 of file agvs_robot_control.cpp.

double AGVSControllerClass::lin_acc_z_

Definition at line 168 of file agvs_robot_control.cpp.

double AGVSControllerClass::linearSpeedXMps_

Definition at line 130 of file agvs_robot_control.cpp.

double AGVSControllerClass::linearSpeedYMps_

Definition at line 131 of file agvs_robot_control.cpp.

ros::NodeHandle AGVSControllerClass::node_handle_

Definition at line 72 of file agvs_robot_control.cpp.

tf::TransformBroadcaster AGVSControllerClass::odom_broadcaster

Definition at line 184 of file agvs_robot_control.cpp.

ros::Publisher AGVSControllerClass::odom_pub_

Definition at line 181 of file agvs_robot_control.cpp.

double AGVSControllerClass::orientation_diff_w_

Definition at line 173 of file agvs_robot_control.cpp.

double AGVSControllerClass::orientation_diff_x_

Definition at line 170 of file agvs_robot_control.cpp.

double AGVSControllerClass::orientation_diff_y_

Definition at line 171 of file agvs_robot_control.cpp.

double AGVSControllerClass::orientation_diff_z_

Definition at line 172 of file agvs_robot_control.cpp.

ros::NodeHandle AGVSControllerClass::private_node_handle_

Definition at line 73 of file agvs_robot_control.cpp.

bool AGVSControllerClass::publish_odom_tf_

Definition at line 176 of file agvs_robot_control.cpp.

bool AGVSControllerClass::read_state_

Definition at line 155 of file agvs_robot_control.cpp.

ros::Publisher AGVSControllerClass::ref_pos_bwd_

Definition at line 90 of file agvs_robot_control.cpp.

ros::Publisher AGVSControllerClass::ref_pos_elevator_

Definition at line 91 of file agvs_robot_control.cpp.

ros::Publisher AGVSControllerClass::ref_pos_fwd_

Definition at line 89 of file agvs_robot_control.cpp.

ros::Publisher AGVSControllerClass::ref_vel_bwd_

Definition at line 88 of file agvs_robot_control.cpp.

ros::Publisher AGVSControllerClass::ref_vel_fwd_

Definition at line 87 of file agvs_robot_control.cpp.

std::string AGVSControllerClass::robot_model_

Definition at line 84 of file agvs_robot_control.cpp.

double AGVSControllerClass::robot_pose_pa_

Definition at line 137 of file agvs_robot_control.cpp.

double AGVSControllerClass::robot_pose_px_

Definition at line 135 of file agvs_robot_control.cpp.

double AGVSControllerClass::robot_pose_py_

Definition at line 136 of file agvs_robot_control.cpp.

double AGVSControllerClass::robot_pose_vx_

Definition at line 138 of file agvs_robot_control.cpp.

double AGVSControllerClass::robot_pose_vy_

Definition at line 139 of file agvs_robot_control.cpp.

ros::ServiceServer AGVSControllerClass::srv_GetMode_

Definition at line 102 of file agvs_robot_control.cpp.

ros::ServiceServer AGVSControllerClass::srv_LowerElevator_

Definition at line 104 of file agvs_robot_control.cpp.

ros::ServiceServer AGVSControllerClass::srv_RaiseElevator_

Definition at line 103 of file agvs_robot_control.cpp.

ros::ServiceServer AGVSControllerClass::srv_SetMode_

Definition at line 101 of file agvs_robot_control.cpp.

ros::ServiceServer AGVSControllerClass::srv_SetOdometry_

Definition at line 100 of file agvs_robot_control.cpp.

diagnostic_updater::HeaderlessTopicDiagnostic* AGVSControllerClass::subs_command_freq

Definition at line 79 of file agvs_robot_control.cpp.

double AGVSControllerClass::v_mps_

Definition at line 152 of file agvs_robot_control.cpp.

double AGVSControllerClass::v_ref_

Definition at line 149 of file agvs_robot_control.cpp.


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


agvs_robot_control
Author(s): Roberto Guzmán
autogenerated on Mon Jun 10 2019 12:47:24