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

Public Member Functions

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

Private Types

typedef actionlib::SimpleActionClient< control_msgs::GripperCommandAction > client_t
 

Private Attributes

boost::shared_ptr< client_tclient_
 
int close_button_
 
int deadman_
 
double max_effort_
 
double max_position_
 
double min_position_
 
int open_button_
 
bool req_close_
 
bool req_open_
 

Additional Inherited Members

- Protected Attributes inherited from TeleopComponent
bool active_
 

Detailed Description

Definition at line 370 of file joystick_teleop.cpp.

Member Typedef Documentation

◆ client_t

typedef actionlib::SimpleActionClient<control_msgs::GripperCommandAction> GripperTeleop::client_t
private

Definition at line 372 of file joystick_teleop.cpp.

Constructor & Destructor Documentation

◆ GripperTeleop()

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

Definition at line 375 of file joystick_teleop.cpp.

Member Function Documentation

◆ publish()

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

Implements TeleopComponent.

Definition at line 418 of file joystick_teleop.cpp.

◆ update()

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

Implements TeleopComponent.

Definition at line 401 of file joystick_teleop.cpp.

Member Data Documentation

◆ client_

boost::shared_ptr<client_t> GripperTeleop::client_
private

Definition at line 442 of file joystick_teleop.cpp.

◆ close_button_

int GripperTeleop::close_button_
private

Definition at line 439 of file joystick_teleop.cpp.

◆ deadman_

int GripperTeleop::deadman_
private

Definition at line 439 of file joystick_teleop.cpp.

◆ max_effort_

double GripperTeleop::max_effort_
private

Definition at line 440 of file joystick_teleop.cpp.

◆ max_position_

double GripperTeleop::max_position_
private

Definition at line 440 of file joystick_teleop.cpp.

◆ min_position_

double GripperTeleop::min_position_
private

Definition at line 440 of file joystick_teleop.cpp.

◆ open_button_

int GripperTeleop::open_button_
private

Definition at line 439 of file joystick_teleop.cpp.

◆ req_close_

bool GripperTeleop::req_close_
private

Definition at line 441 of file joystick_teleop.cpp.

◆ req_open_

bool GripperTeleop::req_open_
private

Definition at line 441 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