#include <joint_position_controller.h>
|
typedef std::vector< hardware_interface::InterfaceResources > | ClaimedResources |
|
enum | ControllerState {
ControllerState::CONSTRUCTED,
ControllerState::INITIALIZED,
ControllerState::RUNNING,
ControllerState::STOPPED,
ControllerState::WAITING,
ControllerState::ABORTED
} |
|
ControllerState | state_ |
|
bool | initRequest (hardware_interface::RobotHW *robot_hw, ros::NodeHandle &root_nh, ros::NodeHandle &controller_nh, ClaimedResources &claimed_resources) override |
|
static void | clearClaims (hardware_interface::RobotHW *robot_hw) |
|
static void | extractInterfaceResources (hardware_interface::RobotHW *robot_hw_in, hardware_interface::RobotHW *robot_hw_out) |
|
static bool | hasRequiredInterfaces (hardware_interface::RobotHW *robot_hw) |
|
static void | populateClaimedResources (hardware_interface::RobotHW *robot_hw, ClaimedResources &claimed_resources) |
|
bool | allow_optional_interfaces_ |
|
hardware_interface::RobotHW | robot_hw_ctrl_ |
|
Definition at line 17 of file joint_position_controller.h.
◆ cubicInterpolation()
double serl_franka_controllers::JointPositionController::cubicInterpolation |
( |
double |
p0, |
|
|
double |
p1, |
|
|
double |
t |
|
) |
| |
|
private |
◆ init()
◆ starting()
void serl_franka_controllers::JointPositionController::starting |
( |
const ros::Time & |
| ) |
|
|
overridevirtual |
◆ update()
void serl_franka_controllers::JointPositionController::update |
( |
const ros::Time & |
, |
|
|
const ros::Duration & |
period |
|
) |
| |
|
overridevirtual |
◆ elapsed_time_
ros::Duration serl_franka_controllers::JointPositionController::elapsed_time_ |
|
private |
◆ initial_pose_
std::array<double, 7> serl_franka_controllers::JointPositionController::initial_pose_ {} |
|
private |
◆ position_joint_handles_
◆ position_joint_interface_
◆ reset_pose_
std::array<double, 7> serl_franka_controllers::JointPositionController::reset_pose_ {} |
|
private |
The documentation for this class was generated from the following files: