MoveIt Pro API
Core Behaviors for MoveIt Pro
Loading...
Searching...
No Matches
moveit_pro_controllers Namespace Reference

Classes

class  Admittance
 
struct  AdmittanceKinematics
 
struct  AdmittanceParameters
 
struct  AdmittanceState
 
class  IOController
 
class  JointTrajectoryAdmittanceController
 
struct  JointTrajectoryAdmittanceControllerCommand
 
class  RealtimeTriggerServiceMonitor
 
class  RobotTestFixture
 
class  RobotTestFixtureInvalidParams
 
class  SecondOrderButterworthFilter
 
struct  StopTrajectory
 
class  TrajectorySampler
 
struct  UtilizedInterfaces
 
class  VelocityForceController
 
struct  VelocityForceParameters
 
class  VelocityForceSetpointGenerator
 

Typedefs

using ForwardKinematicsFn = std::function< bool(const Eigen::VectorNd &reference_joint_values, const Eigen::VectorNd &current_joint_values, AdmittanceState &state)>
 
using DiffInverseKinematicsFn = std::function< bool(const Eigen::VectorNd &joint_values, const Eigen::Vector6d &cartesian_delta, Eigen::VectorNd &joint_deltas)>
 
template<typename T >
using InterfaceReferences = std::vector< std::vector< std::reference_wrapper< T > > >
 
using CallbackReturn = rclcpp_lifecycle::node_interfaces::LifecycleNodeInterface::CallbackReturn
 

Enumerations

enum class  AdmittanceResult { SUCCESS , ERROR_COMPUTING_TRANSFORMS , ERROR_COMPUTING_ADMITTANCE_OFFSET }
 
enum class  InterpolationResult {
  SUCCESS , INVALID_INPUT_MISSING_POSITIONS , INVALID_INPUT_MISSING_VELOCITIES , INVALID_INPUT_TIME_OUT_OF_BOUNDS ,
  INVALID_INPUT_MISMATCHED_SIZES
}
 
enum class  ValidationResult { SUCCESS , INVALID_TRAJECTORY_LENGTH , INVALID_TIME_DOES_NOT_INCREASE }
 
enum class  SamplingResult { SUCCESS , TIME_AT_END , NOT_STARTED , ERROR_SAMPLING_BACKWARDS }
 

Functions

Eigen::Vector3d applyDeadband (const Eigen::Vector3d &signal, double threshold)
 
StopTrajectory computeStopTrajectory (const TimedJointState &initial_state, const Eigen::VectorNd &acceleration_limits)
 
TimedJointState sampleStopTrajectory (const StopTrajectory &stop_trajectory, double time_from_start)
 
Eigen::Vector6d substractGravity (const Eigen::Vector6d &sensor_wrench, const Eigen::Isometry3d &world_pose_sensor, const Eigen::Isometry3d &world_pose_ee, const AdmittanceParameters &parameters)
 
InterpolationResult interpolate (const TimedJointState &state_a, const TimedJointState &state_b, Duration time_from_start, TimedJointState &output)
 
bool isMonotonicallyIncreasing (const Trajectory &trajectory)
 
tl::expected< Trajectory, std::string > trajectoryFromROSMsg (const trajectory_msgs::msg::JointTrajectory &joint_trajectory)
 
bool vectorContainsString (const std::vector< std::string > &vec, const std::string &str)
 
template<class T >
UtilizedInterfaces initializeInterfaceReferences (const std::vector< std::string > &interface_names, InterfaceReferences< T > &interface_references)
 
template<class T >
bool getOrderedInterfaces (const rclcpp::Logger &logger, const std::vector< std::string > &joint_names, std::vector< T > &unordered_interfaces, const std::vector< std::string > &interface_names, InterfaceReferences< T > &ordered_interfaces)
 
controller_interface::InterfaceConfiguration createInterfaceConfiguration (const std::vector< std::string > &joint_names, const std::vector< std::string > &interface_names)
 
void releaseStateAndCommandInterfaces (InterfaceReferences< hardware_interface::LoanedStateInterface > &state_interfaces, InterfaceReferences< hardware_interface::LoanedCommandInterface > &command_interfaces)
 
template<typename T >
void writeToCommandInterface (const T &joint_interface, const Eigen::VectorNd &values)
 
template<typename T >
void writeToCommandInterfaces (const T &joint_interfaces, const TimedJointState &joint_state, const UtilizedInterfaces &interfaces)
 
template<typename T >
Eigen::VectorNd readFromInterface (const T &joint_interface)
 
template<typename T >
TimedJointState readFromInterfaces (const T &joint_interfaces, const UtilizedInterfaces &interfaces)
 
bool initializeForceTorqueSensor (const std::string &ft_sensor_name, double ft_cutoff_frequency_ratio, std::unique_ptr< semantic_components::ForceTorqueSensor > &force_torque_sensor, std::unique_ptr< SecondOrderButterworthFilter > &ft_filter)
 
Eigen::Vector6d getSensedWrench (semantic_components::ForceTorqueSensor &force_torque_sensor)
 
void toStdVector (const Eigen::VectorNd &vector_eigen, std::vector< double > &vector_std)
 
void computeCartesianStopTrajectory (const TimedJointState &initial_state, const VelocityForceParameters &parameters, Duration control_period, std::vector< TimedJointState > &stop_trajectory)
 

Variables

constexpr auto kTestRobotURDF
 
const std::string kForceTorqueSensorName = "tcp_fts_sensor"
 
constexpr auto kEnableService = "enable"
 
constexpr auto kDisableService = "disable"
 
constexpr auto kJointTrajectoryAdmittanceControllerActionName = "/follow_joint_trajectory"
 
constexpr auto kJointTrajectoryAdmittanceControllerTopicName = "~/controller_state"
 
const std::vector< std::string > kAllowedInterfaceTypes
 

Typedef Documentation

◆ CallbackReturn

using moveit_pro_controllers::CallbackReturn = typedef rclcpp_lifecycle::node_interfaces::LifecycleNodeInterface::CallbackReturn

◆ DiffInverseKinematicsFn

typedef std::function< bool(const Eigen::VectorNd &joint_values, const Eigen::Vector6d &cartesian_delta, const Eigen::VectorNd &nullspace_component, Eigen::VectorNd &joint_deltas)> moveit_pro_controllers::DiffInverseKinematicsFn

◆ ForwardKinematicsFn

using moveit_pro_controllers::ForwardKinematicsFn = typedef std::function<bool(const Eigen::VectorNd& reference_joint_values, const Eigen::VectorNd& current_joint_values, AdmittanceState& state)>

◆ InterfaceReferences

template<typename T >
using moveit_pro_controllers::InterfaceReferences = typedef std::vector<std::vector<std::reference_wrapper<T> >>

Enumeration Type Documentation

◆ AdmittanceResult

Enumerator
SUCCESS 
ERROR_COMPUTING_TRANSFORMS 
ERROR_COMPUTING_ADMITTANCE_OFFSET 

◆ InterpolationResult

Enumerator
SUCCESS 
INVALID_INPUT_MISSING_POSITIONS 
INVALID_INPUT_MISSING_VELOCITIES 
INVALID_INPUT_TIME_OUT_OF_BOUNDS 
INVALID_INPUT_MISMATCHED_SIZES 

◆ SamplingResult

Enumerator
SUCCESS 
TIME_AT_END 
NOT_STARTED 
ERROR_SAMPLING_BACKWARDS 

◆ ValidationResult

Enumerator
SUCCESS 
INVALID_TRAJECTORY_LENGTH 
INVALID_TIME_DOES_NOT_INCREASE 

Function Documentation

◆ applyDeadband()

Eigen::Vector3d moveit_pro_controllers::applyDeadband ( const Eigen::Vector3d &  signal,
double  threshold 
)

Applies a deadband to the input vector. Values below the threshold will be set to zero. The threshold will be subtracted/added to values exceeding threshold. / / / / / => --— / / / /

Parameters
[in]signala 3D vector with the signal to filter with a deadband.
[in]thresholdthe deadband threshold.
Returns
the vector with deadband applied.

◆ computeCartesianStopTrajectory()

void moveit_pro_controllers::computeCartesianStopTrajectory ( const TimedJointState &  initial_state,
const VelocityForceParameters parameters,
Duration  control_period,
std::vector< TimedJointState > &  stop_trajectory 
)

◆ computeStopTrajectory()

StopTrajectory moveit_pro_controllers::computeStopTrajectory ( const TimedJointState &  initial_state,
const Eigen::VectorNd &  acceleration_limits 
)

◆ createInterfaceConfiguration()

controller_interface::InterfaceConfiguration moveit_pro_controllers::createInterfaceConfiguration ( const std::vector< std::string > &  joint_names,
const std::vector< std::string > &  interface_names 
)

◆ getOrderedInterfaces()

template<class T >
bool moveit_pro_controllers::getOrderedInterfaces ( const rclcpp::Logger &  logger,
const std::vector< std::string > &  joint_names,
std::vector< T > &  unordered_interfaces,
const std::vector< std::string > &  interface_names,
InterfaceReferences< T > &  ordered_interfaces 
)

◆ getSensedWrench()

Eigen::Vector6d moveit_pro_controllers::getSensedWrench ( semantic_components::ForceTorqueSensor &  force_torque_sensor)

◆ initializeForceTorqueSensor()

bool moveit_pro_controllers::initializeForceTorqueSensor ( const std::string &  ft_sensor_name,
double  ft_cutoff_frequency_ratio,
std::unique_ptr< semantic_components::ForceTorqueSensor > &  force_torque_sensor,
std::unique_ptr< SecondOrderButterworthFilter > &  ft_filter 
)

◆ initializeInterfaceReferences()

template<class T >
UtilizedInterfaces moveit_pro_controllers::initializeInterfaceReferences ( const std::vector< std::string > &  interface_names,
InterfaceReferences< T > &  interface_references 
)

◆ interpolate()

InterpolationResult moveit_pro_controllers::interpolate ( const TimedJointState &  state_a,
const TimedJointState &  state_b,
Duration  time_from_start,
TimedJointState &  output 
)

◆ isMonotonicallyIncreasing()

bool moveit_pro_controllers::isMonotonicallyIncreasing ( const Trajectory &  trajectory)

◆ readFromInterface()

template<typename T >
Eigen::VectorNd moveit_pro_controllers::readFromInterface ( const T &  joint_interface)

◆ readFromInterfaces()

template<typename T >
TimedJointState moveit_pro_controllers::readFromInterfaces ( const T &  joint_interfaces,
const UtilizedInterfaces interfaces 
)

◆ releaseStateAndCommandInterfaces()

void moveit_pro_controllers::releaseStateAndCommandInterfaces ( InterfaceReferences< hardware_interface::LoanedStateInterface > &  state_interfaces,
InterfaceReferences< hardware_interface::LoanedCommandInterface > &  command_interfaces 
)

◆ sampleStopTrajectory()

TimedJointState moveit_pro_controllers::sampleStopTrajectory ( const StopTrajectory stop_trajectory,
double  time_from_start 
)

◆ substractGravity()

Eigen::Vector6d moveit_pro_controllers::substractGravity ( const Eigen::Vector6d &  sensor_wrench,
const Eigen::Isometry3d &  world_pose_sensor,
const Eigen::Isometry3d &  world_pose_ee,
const AdmittanceParameters parameters 
)

◆ toStdVector()

void moveit_pro_controllers::toStdVector ( const Eigen::VectorNd &  vector_eigen,
std::vector< double > &  vector_std 
)

◆ trajectoryFromROSMsg()

tl::expected< Trajectory, std::string > moveit_pro_controllers::trajectoryFromROSMsg ( const trajectory_msgs::msg::JointTrajectory &  joint_trajectory)

◆ vectorContainsString()

bool moveit_pro_controllers::vectorContainsString ( const std::vector< std::string > &  vec,
const std::string &  str 
)
inline

◆ writeToCommandInterface()

template<typename T >
void moveit_pro_controllers::writeToCommandInterface ( const T &  joint_interface,
const Eigen::VectorNd &  values 
)

◆ writeToCommandInterfaces()

template<typename T >
void moveit_pro_controllers::writeToCommandInterfaces ( const T &  joint_interfaces,
const TimedJointState &  joint_state,
const UtilizedInterfaces interfaces 
)

Variable Documentation

◆ kAllowedInterfaceTypes

const std::vector<std::string> moveit_pro_controllers::kAllowedInterfaceTypes
Initial value:
= {
hardware_interface::HW_IF_POSITION,
hardware_interface::HW_IF_VELOCITY,
hardware_interface::HW_IF_ACCELERATION,
}

◆ kDisableService

constexpr auto moveit_pro_controllers::kDisableService = "disable"
constexpr

◆ kEnableService

constexpr auto moveit_pro_controllers::kEnableService = "enable"
constexpr

◆ kForceTorqueSensorName

const std::string moveit_pro_controllers::kForceTorqueSensorName = "tcp_fts_sensor"
inline

◆ kJointTrajectoryAdmittanceControllerActionName

constexpr auto moveit_pro_controllers::kJointTrajectoryAdmittanceControllerActionName = "/follow_joint_trajectory"
inlineconstexpr

◆ kJointTrajectoryAdmittanceControllerTopicName

constexpr auto moveit_pro_controllers::kJointTrajectoryAdmittanceControllerTopicName = "~/controller_state"
inlineconstexpr

◆ kTestRobotURDF

constexpr auto moveit_pro_controllers::kTestRobotURDF
constexpr