Public Member Functions | Private Member Functions | Private Attributes | List of all members
BaseTeleop Class Reference
Inheritance diagram for BaseTeleop:
Inheritance graph
[legend]

Public Member Functions

 BaseTeleop (const std::string &name, ros::NodeHandle &nh)
 
virtual void publish (const ros::Duration &dt)
 
virtual bool start ()
 
virtual bool stop ()
 
virtual bool update (const sensor_msgs::Joy::ConstPtr &joy, const sensor_msgs::JointState::ConstPtr &state)
 
- Public Member Functions inherited from TeleopComponent
 TeleopComponent ()
 
virtual ~TeleopComponent ()
 

Private Member Functions

void odomCallback (const nav_msgs::OdometryConstPtr &odom)
 

Private Attributes

int axis_w_
 
int axis_x_
 
ros::Publisher cmd_vel_pub_
 
int deadman_
 
geometry_msgs::Twist desired_
 
geometry_msgs::Twist last_
 
double max_acc_w_
 
double max_acc_x_
 
double max_vel_w_
 
double max_vel_x_
 
double max_windup_time
 
double min_vel_x_
 
ros::ServiceClient mux_
 
nav_msgs::Odometry odom_
 
boost::mutex odom_mutex_
 
ros::Subscriber odom_sub_
 
std::string prev_mux_topic_
 
bool use_mux_
 

Additional Inherited Members

- Protected Attributes inherited from TeleopComponent
bool active_
 

Detailed Description

Definition at line 92 of file joystick_teleop.cpp.

Constructor & Destructor Documentation

◆ BaseTeleop()

BaseTeleop::BaseTeleop ( const std::string &  name,
ros::NodeHandle nh 
)
inline

Definition at line 95 of file joystick_teleop.cpp.

Member Function Documentation

◆ odomCallback()

void BaseTeleop::odomCallback ( const nav_msgs::OdometryConstPtr &  odom)
inlineprivate

Definition at line 215 of file joystick_teleop.cpp.

◆ publish()

virtual void BaseTeleop::publish ( const ros::Duration dt)
inlinevirtual

Implements TeleopComponent.

Definition at line 148 of file joystick_teleop.cpp.

◆ start()

virtual bool BaseTeleop::start ( )
inlinevirtual

Reimplemented from TeleopComponent.

Definition at line 174 of file joystick_teleop.cpp.

◆ stop()

virtual bool BaseTeleop::stop ( )
inlinevirtual

Reimplemented from TeleopComponent.

Definition at line 194 of file joystick_teleop.cpp.

◆ update()

virtual bool BaseTeleop::update ( const sensor_msgs::Joy::ConstPtr &  joy,
const sensor_msgs::JointState::ConstPtr &  state 
)
inlinevirtual

Implements TeleopComponent.

Definition at line 125 of file joystick_teleop.cpp.

Member Data Documentation

◆ axis_w_

int BaseTeleop::axis_w_
private

Definition at line 223 of file joystick_teleop.cpp.

◆ axis_x_

int BaseTeleop::axis_x_
private

Definition at line 223 of file joystick_teleop.cpp.

◆ cmd_vel_pub_

ros::Publisher BaseTeleop::cmd_vel_pub_
private

Definition at line 235 of file joystick_teleop.cpp.

◆ deadman_

int BaseTeleop::deadman_
private

Definition at line 223 of file joystick_teleop.cpp.

◆ desired_

geometry_msgs::Twist BaseTeleop::desired_
private

Definition at line 244 of file joystick_teleop.cpp.

◆ last_

geometry_msgs::Twist BaseTeleop::last_
private

Definition at line 245 of file joystick_teleop.cpp.

◆ max_acc_w_

double BaseTeleop::max_acc_w_
private

Definition at line 227 of file joystick_teleop.cpp.

◆ max_acc_x_

double BaseTeleop::max_acc_x_
private

Definition at line 227 of file joystick_teleop.cpp.

◆ max_vel_w_

double BaseTeleop::max_vel_w_
private

Definition at line 226 of file joystick_teleop.cpp.

◆ max_vel_x_

double BaseTeleop::max_vel_x_
private

Definition at line 226 of file joystick_teleop.cpp.

◆ max_windup_time

double BaseTeleop::max_windup_time
private

Definition at line 242 of file joystick_teleop.cpp.

◆ min_vel_x_

double BaseTeleop::min_vel_x_
private

Definition at line 226 of file joystick_teleop.cpp.

◆ mux_

ros::ServiceClient BaseTeleop::mux_
private

Definition at line 232 of file joystick_teleop.cpp.

◆ odom_

nav_msgs::Odometry BaseTeleop::odom_
private

Definition at line 240 of file joystick_teleop.cpp.

◆ odom_mutex_

boost::mutex BaseTeleop::odom_mutex_
private

Definition at line 239 of file joystick_teleop.cpp.

◆ odom_sub_

ros::Subscriber BaseTeleop::odom_sub_
private

Definition at line 236 of file joystick_teleop.cpp.

◆ prev_mux_topic_

std::string BaseTeleop::prev_mux_topic_
private

Definition at line 231 of file joystick_teleop.cpp.

◆ use_mux_

bool BaseTeleop::use_mux_
private

Definition at line 230 of file joystick_teleop.cpp.


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


fetch_teleop
Author(s): Michael Ferguson
autogenerated on Mon Feb 28 2022 22:24:06