#include <boost/thread.hpp>#include <boost/noncopyable.hpp>#include <ros/ros.h>#include <actionlib/server/simple_action_server.h>#include <urdf/model.h>#include <tf/transform_broadcaster.h>#include <std_msgs/Int8.h>#include <metralabs_msgs/IDAndFloat.h>#include <metralabs_msgs/SchunkStatus.h>#include <sensor_msgs/JointState.h>#include <trajectory_msgs/JointTrajectory.h>#include <control_msgs/JointTrajectoryControllerState.h>#include <control_msgs/FollowJointTrajectoryAction.h>#include "RobotArm.h"#include "AmtecProtocolArm.h"#include "SchunkProtocolArm.h"#include "LWA3ArmUASHH.h"#include "PowerCubeArmUUISRC.h"

Go to the source code of this file.
Classes | |
| class | SchunkServer |
| class | TrajectoryExecuter |
Defines | |
| #define | DEG_TO_RAD(d) ((d)*M_PI/180.0) |
| #define | RAD_TO_DEG(r) ((r)*180.0/M_PI) |
| #define | SIGN_TOLERANT_CUT(value, lim) |
| #define | SIGN_TOLERANT_MAX(value, def) |
| #define | SLOWEST_REASONABLE_JOINT_SPEED 0.015f |
| #define | TOO_SLOW 0.002f |
| #define DEG_TO_RAD | ( | d | ) | ((d)*M_PI/180.0) |
Definition at line 33 of file SchunkServer.h.
| #define RAD_TO_DEG | ( | r | ) | ((r)*180.0/M_PI) |
Definition at line 34 of file SchunkServer.h.
| #define SIGN_TOLERANT_CUT | ( | value, | |
| lim | |||
| ) |
( (value)==0 ? 0 : \
( \
(value)>0 ? \
( (value) > (lim) ? (value) : (0) ) : \
( (value) < -(lim) ? (value) : (0) ) \
) \
)
| #define SIGN_TOLERANT_MAX | ( | value, | |
| def | |||
| ) |
( (value)==0 ? 0 : \
( \
(value)>0 ? \
std::max((value), (def)) : \
std::min((value), -(def)) \
) \
)
| #define SLOWEST_REASONABLE_JOINT_SPEED 0.015f |
Definition at line 36 of file SchunkServer.h.
| #define TOO_SLOW 0.002f |
Definition at line 37 of file SchunkServer.h.