Drake
Drake C++ Documentation
drake::manipulation::util Namespace Reference

Classes

class  MoveIkDemoBase
 This class provides some common functionality for generating IK plans for robot arms, including things like creating a MultibodyPlant, setting joint velocity limits, implementing a robot status update handler suitable for invoking from an LCM callback, and generating plans to move a specified link to a goal configuration. More...
 
class  MovingAverageFilter
 The implementation of a Moving Average Filter. More...
 
class  RobotPlanInterpolator
 This class implements a source of joint positions for a robot. More...
 

Enumerations

enum  InterpolatorType { ZeroOrderHold, FirstOrderHold, Pchip, Cubic }
 This enum specifies the type of interpolator to use in constructing the piece-wise polynomial. More...
 

Functions

template<typename T >
std::vector< std::string > GetJointNames (const multibody::MultibodyPlant< T > &plant)
 
void ApplyJointVelocityLimits (const std::vector< Eigen::VectorXd > &keyframes, const Eigen::VectorXd &limits, std::vector< double > *times)
 Scales a plan so that no step exceeds the robot's maximum joint velocities. More...
 
lcmt_robot_plan EncodeKeyFrames (const std::vector< std::string > &joint_names, const std::vector< double > &times, const std::vector< Eigen::VectorXd > &keyframes)
 Makes an lcmt_robot_plan message. More...
 

Enumeration Type Documentation

◆ InterpolatorType

enum InterpolatorType
strong

This enum specifies the type of interpolator to use in constructing the piece-wise polynomial.

Enumerator
ZeroOrderHold 
FirstOrderHold 
Pchip 
Cubic 

Function Documentation

◆ ApplyJointVelocityLimits()

void drake::manipulation::util::ApplyJointVelocityLimits ( const std::vector< Eigen::VectorXd > &  keyframes,
const Eigen::VectorXd &  limits,
std::vector< double > *  times 
)

Scales a plan so that no step exceeds the robot's maximum joint velocities.

The size of keyframes must match the size of times. Times must be in strictly increasing order and start with zero. Per-joint velocity limits are specified by limits, which much be the same size ad the number of joints in each element of keyframes. Assumes that velocity limits are equal regardless of direction. If any step does exceed the maximum velocities in limits, times will be modified to reduce the velocity.

◆ EncodeKeyFrames()

lcmt_robot_plan drake::manipulation::util::EncodeKeyFrames ( const std::vector< std::string > &  joint_names,
const std::vector< double > &  times,
const std::vector< Eigen::VectorXd > &  keyframes 
)

Makes an lcmt_robot_plan message.

The entries in joint_names should be unique, though the behavior if names are duplicated depends on how the returned plan is evaluated. The size of each vector in keyframes must match the size of joint_names. The size of keyframes must match the size of times. Times must be in strictly increasing order.

◆ GetJointNames()

std::vector<std::string> drake::manipulation::util::GetJointNames ( const multibody::MultibodyPlant< T > &  plant)
Returns
A vector of joint names corresponding to the positions in plant in the order of the joint indices. If joints with duplicate names exist in different model instance in the plant, the names will be duplicated in the output.