All Classes Namespaces Files Functions Variables Typedefs
Functions | Variables
gripper_actuator.cpp File Reference
#include <ros/ros.h>
#include <string>
#include <std_msgs/Float32.h>
#include <std_msgs/String.h>
#include <std_msgs/Bool.h>
#include <Grijper/command.h>
#include <threemxl/C3mxlROS.h>
Include dependency graph for gripper_actuator.cpp:

Go to the source code of this file.

Functions

float calc_current (float force)
 Conversion method to convert a target force into a current. More...
 
bool close ()
 Small controlling method for closing the gripper. More...
 
void gripperControl (const Grijper::command::ConstPtr &msg)
 This method controls the motor. More...
 
int main (int argc, char **argv)
 Main method of this node. All commands are evaluated here, and motor actuation is controlled from here. More...
 
bool open ()
 Small controlling method for opening the gripper. More...
 
bool relax ()
 Small controlling method for relaxing the gripper. More...
 
void shutdown (const std_msgs::Bool::ConstPtr &b)
 Controll method to shutdown this ROS node when the command is given. More...
 

Variables

float current = 0.04
 
ros::Publisher gripper_state
 
CDxlGeneric * motor_
 

Function Documentation

float calc_current ( float  force)

Conversion method to convert a target force into a current.

Converts a target force into a current that can be passed on to the motor.

Parameters
forceThe target force as a float.
Returns
The calculated current.

Definition at line 128 of file gripper_actuator.cpp.

bool close ( )

Small controlling method for closing the gripper.

This method closes the gripper with the corresponding force.

Returns
True

Definition at line 99 of file gripper_actuator.cpp.

void gripperControl ( const Grijper::command::ConstPtr msg)

This method controls the motor.

This method is called every time a command from the controller has been given. This command is evaluated and executed. The msg parameter contains the 'cmd' string describing the command to be executed and also a 'force' float that indicates the target force. This target force is converted to a current, which is passed in to the motor, with a sign and magnitude according to the command.

Parameters
msgThe message containing the command and target force.

Definition at line 63 of file gripper_actuator.cpp.

int main ( int  argc,
char **  argv 
)

Main method of this node. All commands are evaluated here, and motor actuation is controlled from here.

This method controls the motor powering the gripper. This also meand publishing the gripper state when it has changed.

This node also listens to the shutdown command given by the controller.

Definition at line 28 of file gripper_actuator.cpp.

bool open ( )

Small controlling method for opening the gripper.

This method opens the gripper with the corresponding force.

Returns
True

Definition at line 85 of file gripper_actuator.cpp.

bool relax ( )

Small controlling method for relaxing the gripper.

This method relaxed the gripper.

Returns
True

Definition at line 113 of file gripper_actuator.cpp.

void shutdown ( const std_msgs::Bool::ConstPtr &  b)

Controll method to shutdown this ROS node when the command is given.

This method will shutdown this node when the command is given by the console.

Parameters
bThe message containing the command. Nothing is done with the command since we know what it will be when this message is received.

Definition at line 137 of file gripper_actuator.cpp.

Variable Documentation

float current = 0.04

Target current variable, default is set to 0.04.

Definition at line 18 of file gripper_actuator.cpp.

ros::Publisher gripper_state

Gripper state publisher.

Definition at line 12 of file gripper_actuator.cpp.

CDxlGeneric* motor_

Threemxl generic motor controller pointer.

Definition at line 19 of file gripper_actuator.cpp.



Grijper
Author(s): Stijn van Schooten, Wybren ten Cate, Florens Kreuk, Jan Wymenga,Joris Coenen, Roy Groot
autogenerated on Thu Oct 3 2013 22:59:42