#include <pr2_controller_interface/controller.h>
#include <pr2_mechanism_model/chain.h>
#include <pr2_mechanism_model/robot.h>
#include <boost/scoped_ptr.hpp>
#include <kdl/chain.hpp>
#include <kdl/chainjnttojacsolver.hpp>
#include <kdl/chainfksolverpos_recursive.hpp>
#include <kdl/frames.hpp>
#include <kdl/jacobian.hpp>
#include <kdl/jntarray.hpp>
#include <realtime_tools/realtime_publisher.h>
#include <realtime_tools/realtime_box.h>
#include <ros/ros.h>
#include <ee_cart_imped_msgs/EECartImpedAction.h>
#include <ee_cart_imped_msgs/EECartImpedGoal.h>
#include <ee_cart_imped_msgs/StiffPoint.h>
Go to the source code of this file.
Classes | |
class | ee_cart_imped_control_ns::EECartImpedControlClass |
Allows a user to control the force or stiffness applied by joints. More... | |
class | ee_cart_imped_control_ns::EECartImpedControlClass::EECartImpedData |
Class for storing a trajectory and associated information. More... | |
Namespaces | |
namespace | ee_cart_imped_control_ns |
Defines | |
#define | ACCEPTABLE_ROT_STIFFNESS 100.0 |
Maximum stiffness for rotation. | |
#define | MAX_STIFFNESS 1000.0 |
Maximum stiffness for translation. |
#define ACCEPTABLE_ROT_STIFFNESS 100.0 |
Maximum stiffness for rotation.
Definition at line 29 of file ee_cart_imped_control.hpp.
#define MAX_STIFFNESS 1000.0 |
Maximum stiffness for translation.
Definition at line 26 of file ee_cart_imped_control.hpp.