#include <ros/ros.h>
#include <sensor_msgs/JointState.h>
#include <string>
#include <vector>
#include <memory>
#include <unordered_map>
#include <fstream>
#include <Eigen/Dense>
#include <yaml-cpp/yaml.h>
#include <end_effector/Utils.h>
#include <end_effector/UtilsEigen.h>
#include <end_effector/UtilsYAML.h>
#include <rosee_msg/HandInfo.h>
#include <rosee_msg/MotorPhalangePressure.h>
Go to the source code of this file.
#define HAL_CREATE_OBJECT |
( |
|
className | ) |
|
Value:extern "C" ::ROSEE::EEHal* create_object_##className ( ros::NodeHandle* nh) { \
return new className(nh); \
} \
Class representing an end-effector.
Definition at line 42 of file EEHal.h.