Controller class for ros_control that allows force-feedback teleoperation of a follower arm from a leader arm. More...
#include <teleop_joint_pd_example_controller.h>
Classes | |
struct | FrankaDataContainer |
Public Member Functions | |
bool | init (hardware_interface::RobotHW *robot_hw, ros::NodeHandle &node_handle) override |
Initializes the controller class to be ready to run. More... | |
void | starting (const ros::Time &) override |
Prepares the controller for the real-time execution. More... | |
void | update (const ros::Time &, const ros::Duration &period) override |
Computes the control-law and commands the resulting joint torques to the robots. More... | |
![]() | |
virtual bool | init (hardware_interface::RobotHW *, ros::NodeHandle &, ros::NodeHandle &) |
MultiInterfaceController (bool allow_optional_interfaces=false) | |
![]() | |
virtual void | aborting (const ros::Time &) |
virtual void | aborting (const ros::Time &) |
bool | abortRequest (const ros::Time &time) |
bool | abortRequest (const ros::Time &time) |
ControllerBase ()=default | |
ControllerBase (const ControllerBase &)=delete | |
ControllerBase (ControllerBase &&)=delete | |
bool | isAborted () const |
bool | isAborted () const |
bool | isInitialized () const |
bool | isInitialized () const |
bool | isRunning () const |
bool | isRunning () const |
bool | isStopped () const |
bool | isStopped () const |
bool | isWaiting () const |
bool | isWaiting () const |
ControllerBase & | operator= (const ControllerBase &)=delete |
ControllerBase & | operator= (ControllerBase &&)=delete |
bool | startRequest (const ros::Time &time) |
bool | startRequest (const ros::Time &time) |
virtual void | stopping (const ros::Time &) |
virtual void | stopping (const ros::Time &) |
bool | stopRequest (const ros::Time &time) |
bool | stopRequest (const ros::Time &time) |
void | updateRequest (const ros::Time &time, const ros::Duration &period) |
void | updateRequest (const ros::Time &time, const ros::Duration &period) |
virtual void | waiting (const ros::Time &) |
virtual void | waiting (const ros::Time &) |
bool | waitRequest (const ros::Time &time) |
bool | waitRequest (const ros::Time &time) |
virtual | ~ControllerBase ()=default |
Private Types | |
using | Matrix7d = Eigen::Matrix< double, 7, 7 > |
using | Vector6d = Eigen::Matrix< double, 6, 1 > |
using | Vector7d = Eigen::Matrix< double, 7, 1 > |
Private Member Functions | |
template<typename T > | |
T | get1dParam (const std::string ¶m_name, ros::NodeHandle &nh) |
Vector7d | get7dParam (const std::string ¶m_name, ros::NodeHandle &nh) |
template<typename T > | |
std::vector< T > | getJointParams (const std::string ¶m_name, ros::NodeHandle &nh) |
void | initArm (hardware_interface::RobotHW *robot_hw, ros::NodeHandle &node_handle, FrankaDataContainer &arm_data, const std::string &arm_id, const std::vector< std::string > &joint_names) |
Vector7d | leaderDamping (const Vector7d &dq) |
void | publishFollowerContact () |
void | publishFollowerTarget () |
void | publishLeaderContact () |
void | publishLeaderTarget () |
void | publishMarkers () |
double | rampParameter (double x, double neg_x_asymptote, double pos_x_asymptote, double shift_along_x, double increase_factor) |
Vector7d | saturateAndLimit (const Vector7d &x_calc, const Vector7d &x_last, const Vector7d &x_max, const Vector7d &dx_max, double delta_t) |
void | teleopParamCallback (franka_example_controllers::teleop_paramConfig &config, uint32_t level) |
void | updateArm (FrankaDataContainer &arm_data) |
Static Private Member Functions | |
static void | getJointLimits (ros::NodeHandle &nh, const std::vector< std::string > &joint_names, std::array< double, 7 > &upper_joint_soft_limit, std::array< double, 7 > &lower_joint_soft_limit) |
Controller class for ros_control that allows force-feedback teleoperation of a follower arm from a leader arm.
Smooth tracking is implemented by integrating a velocity signal, which is calculated by limiting and saturating the velocity of the leader arm and a drift compensation. The torque control of the follower arm is implemented by a simple PD-controller. The leader arm is slightly damped to reduce vibrations. Force-feedback is applied to the leader arm when the external forces on the follower arm exceed a configured threshold. While the leader arm is unguided (not in contact), the applied force-feedback will be reduced.
Definition at line 48 of file teleop_joint_pd_example_controller.h.
|
private |
Definition at line 77 of file teleop_joint_pd_example_controller.h.
|
private |
Definition at line 75 of file teleop_joint_pd_example_controller.h.
|
private |
Definition at line 76 of file teleop_joint_pd_example_controller.h.
|
inlineprivate |
Definition at line 180 of file teleop_joint_pd_example_controller.h.
|
private |
Definition at line 504 of file teleop_joint_pd_example_controller.cpp.
|
staticprivate |
Definition at line 425 of file teleop_joint_pd_example_controller.cpp.
|
inlineprivate |
Definition at line 167 of file teleop_joint_pd_example_controller.h.
|
overridevirtual |
Initializes the controller class to be ready to run.
[in] | robot_hw | Pointer to a RobotHW class to get interfaces and resource handles. |
[in] | node_handle | Nodehandle that allows getting parameterizations from the server and starting publisher |
Reimplemented from controller_interface::MultiInterfaceController< hardware_interface::EffortJointInterface, franka_hw::FrankaStateInterface >.
Definition at line 25 of file teleop_joint_pd_example_controller.cpp.
|
private |
Definition at line 139 of file teleop_joint_pd_example_controller.cpp.
|
private |
Definition at line 510 of file teleop_joint_pd_example_controller.cpp.
|
private |
Definition at line 497 of file teleop_joint_pd_example_controller.cpp.
|
private |
Definition at line 478 of file teleop_joint_pd_example_controller.cpp.
|
private |
Definition at line 490 of file teleop_joint_pd_example_controller.cpp.
|
private |
Definition at line 466 of file teleop_joint_pd_example_controller.cpp.
|
private |
Definition at line 529 of file teleop_joint_pd_example_controller.cpp.
|
private |
Definition at line 366 of file teleop_joint_pd_example_controller.cpp.
|
private |
Definition at line 351 of file teleop_joint_pd_example_controller.cpp.
|
overridevirtual |
Prepares the controller for the real-time execution.
This method is executed once every time the controller is started and runs in real-time
Reimplemented from controller_interface::ControllerBase.
Definition at line 194 of file teleop_joint_pd_example_controller.cpp.
|
private |
Definition at line 377 of file teleop_joint_pd_example_controller.cpp.
|
overridevirtual |
Computes the control-law and commands the resulting joint torques to the robots.
[in] | period | The control period (here 0.001s) |
Implements controller_interface::ControllerBase.
Definition at line 215 of file teleop_joint_pd_example_controller.cpp.
|
private |
Definition at line 345 of file teleop_joint_pd_example_controller.cpp.
|
private |
Definition at line 120 of file teleop_joint_pd_example_controller.h.
|
private |
Definition at line 142 of file teleop_joint_pd_example_controller.h.
|
private |
Definition at line 118 of file teleop_joint_pd_example_controller.h.
|
private |
Definition at line 110 of file teleop_joint_pd_example_controller.h.
|
private |
Definition at line 111 of file teleop_joint_pd_example_controller.h.
|
private |
Definition at line 199 of file teleop_joint_pd_example_controller.h.
|
private |
Definition at line 140 of file teleop_joint_pd_example_controller.h.
|
private |
Definition at line 116 of file teleop_joint_pd_example_controller.h.
|
private |
Definition at line 130 of file teleop_joint_pd_example_controller.h.
|
private |
Definition at line 131 of file teleop_joint_pd_example_controller.h.
|
private |
Definition at line 108 of file teleop_joint_pd_example_controller.h.
|
private |
Definition at line 109 of file teleop_joint_pd_example_controller.h.
|
private |
Definition at line 103 of file teleop_joint_pd_example_controller.h.
|
private |
Definition at line 104 of file teleop_joint_pd_example_controller.h.
|
private |
Definition at line 102 of file teleop_joint_pd_example_controller.h.
|
private |
Definition at line 200 of file teleop_joint_pd_example_controller.h.
|
private |
Definition at line 204 of file teleop_joint_pd_example_controller.h.
|
private |
Definition at line 206 of file teleop_joint_pd_example_controller.h.
|
private |
Definition at line 213 of file teleop_joint_pd_example_controller.h.
|
private |
Definition at line 98 of file teleop_joint_pd_example_controller.h.
|
private |
Definition at line 202 of file teleop_joint_pd_example_controller.h.
|
private |
Definition at line 211 of file teleop_joint_pd_example_controller.h.
|
private |
Definition at line 138 of file teleop_joint_pd_example_controller.h.
|
private |
Definition at line 137 of file teleop_joint_pd_example_controller.h.
|
private |
Definition at line 106 of file teleop_joint_pd_example_controller.h.
|
private |
Definition at line 124 of file teleop_joint_pd_example_controller.h.
|
private |
Definition at line 128 of file teleop_joint_pd_example_controller.h.
|
private |
Definition at line 132 of file teleop_joint_pd_example_controller.h.
|
private |
Definition at line 133 of file teleop_joint_pd_example_controller.h.
|
private |
Definition at line 135 of file teleop_joint_pd_example_controller.h.
|
private |
Definition at line 123 of file teleop_joint_pd_example_controller.h.
|
private |
Definition at line 126 of file teleop_joint_pd_example_controller.h.
|
private |
Definition at line 144 of file teleop_joint_pd_example_controller.h.
|
private |
Definition at line 212 of file teleop_joint_pd_example_controller.h.
|
private |
Definition at line 201 of file teleop_joint_pd_example_controller.h.
|
private |
Definition at line 97 of file teleop_joint_pd_example_controller.h.
|
private |
Definition at line 210 of file teleop_joint_pd_example_controller.h.
|
private |
Definition at line 214 of file teleop_joint_pd_example_controller.h.
|
private |
Definition at line 121 of file teleop_joint_pd_example_controller.h.
|
private |
Definition at line 209 of file teleop_joint_pd_example_controller.h.
|
private |
Definition at line 100 of file teleop_joint_pd_example_controller.h.
|
private |
Definition at line 101 of file teleop_joint_pd_example_controller.h.
|
private |
Definition at line 113 of file teleop_joint_pd_example_controller.h.
|
private |
Definition at line 112 of file teleop_joint_pd_example_controller.h.