Classes | |
| class | CartesianPoseController |
| class | CartesianTwistController |
| class | CartesianWrenchController |
| class | Controller |
| class | ControllerLoader |
| class | ControllerManager |
| class | DiffDriveBaseController |
| ROS-aware controller to manage a differential drive mobile base. This subcribes to cmd_vel topic, publishes odom and tf, and manages the two wheel joints. More... | |
| class | FollowJointTrajectoryController |
| This ROS interface implements a FollowJointTrajectoryAction interface for controlling (primarily) robot arms. More... | |
| class | GravityCompensation |
| Controller which uses KDL to compute torque needed for static holding of the chain at the current pose. More... | |
| class | Handle |
| class | JointHandle |
| class | ParallelGripperController |
| Controller for a parallel jaw gripper, is really only intended for use in simulation. More... | |
| class | PID |
| class | PointHeadController |
| class | ScaledMimicController |
| Controller for a having one joint be a (scaled) mimic of another. Primary design use case is making a fake bellows joint that moves in relation to a torso lift joint. More... | |
| struct | Spline |
| Spline. More... | |
| class | SplineTrajectorySampler |
| Sampler that uses splines. More... | |
| struct | Trajectory |
| struct | TrajectoryPoint |
| Basis for a Trajectory Point. More... | |
| class | TrajectorySampler |
| Base class for samplers of trajectories. More... | |
Typedefs | |
| typedef boost::shared_ptr< ControllerLoader > | ControllerLoaderPtr |
| typedef boost::shared_ptr< Controller > | ControllerPtr |
| typedef boost::shared_ptr< DiffDriveBaseController > | DiffDriveBaseControllerPtr |
| typedef boost::shared_ptr< Handle > | HandlePtr |
| typedef boost::shared_ptr< JointHandle > | JointHandlePtr |
Enumerations | |
| enum | SplineType { QUINTIC, CUBIC, LINEAR } |
Functions | |
| static void | CubicSpline (double p0, double v0, double p1, double v1, double t, Spline &s) |
| Constructor for a cubic spline with between (p0,v0) and (p1,v1) More... | |
| static void | generatePowers (int n, double x, double *powers) |
| Helper function for splines. More... | |
| static void | LinearSpline (double p0, double p1, double t, Spline &s) |
| static void | QuinticSpline (double p0, double v0, double a0, double p1, double v1, double a1, double t, Spline &s) |
| Create a quintic spline with between (p0,v0,a0) and (p1,v1,a1) More... | |
| void | rosPrintTrajectory (Trajectory &t) |
| Print trajectory to ROS INFO. More... | |
| static void | sampleCubicSpline (Spline s, double t, double &position, double &velocity) |
| Sample from the spline at time t. More... | |
| static void | sampleLinearSpline (Spline &s, double t, double &position) |
| static void | sampleQuinticSpline (Spline &s, double t, double &position, double &velocity, double &acceleration) |
| Sample from the spline at time t. More... | |
| bool | spliceTrajectories (const Trajectory &t1, const Trajectory &t2, const double time, Trajectory *t) |
| Splice two trajectories. More... | |
| bool | trajectoryFromMsg (const trajectory_msgs::JointTrajectory &message, const std::vector< std::string > joints, Trajectory *trajectory) |
| Convert message into Trajectory. More... | |
| bool | unwindTrajectoryPoint (std::vector< bool > continuous, TrajectoryPoint &p) |
| bool | windupTrajectory (std::vector< bool > continuous, Trajectory &trajectory) |
| Windup the trajectory so that continuous joints do not wrap. More... | |
Definition at line 187 of file diff_drive_base.h.
| Enumerator | |
|---|---|
| QUINTIC | |
| CUBIC | |
| LINEAR | |
Definition at line 54 of file trajectory_spline_sampler.h.
|
static |
Constructor for a cubic spline with between (p0,v0) and (p1,v1)
| p0 | Starting position. |
| v0 | Starting velocity. |
| p1 | Ending position. |
| v1 | Ending velocity. |
| t | Time between start and end. |
| s | Reference to the spline to create. |
Definition at line 149 of file trajectory_spline_sampler.h.
|
inlinestatic |
Helper function for splines.
Definition at line 62 of file trajectory_spline_sampler.h.
|
static |
Definition at line 188 of file trajectory_spline_sampler.h.
|
static |
Create a quintic spline with between (p0,v0,a0) and (p1,v1,a1)
| p0 | Starting position. |
| v0 | Starting velocity. |
| a0 | Starting acceleration. |
| p1 | Ending position. |
| v1 | Ending velocity. |
| a1 | Ending acceleration. |
| t | Time between start and end. |
| s | The spline |
Definition at line 82 of file trajectory_spline_sampler.h.
|
inline |
Print trajectory to ROS INFO.
Definition at line 221 of file trajectory.h.
|
static |
Sample from the spline at time t.
Definition at line 173 of file trajectory_spline_sampler.h.
|
static |
Definition at line 195 of file trajectory_spline_sampler.h.
|
static |
Sample from the spline at time t.
Definition at line 115 of file trajectory_spline_sampler.h.
|
inline |
Splice two trajectories.
| t1 | First trajectory to splice |
| t2 | Second trajectory to splice (will overwrite first) |
| time | The start time for the new trajectory (typically, current system time) |
| t | The new trajectory. |
Definition at line 132 of file trajectory.h.
|
inline |
Convert message into Trajectory.
| message | The trajectory message. |
| joints | Vector of joint names, used to order the values within a TrajectoryPoint |
| trajectory | The returned trajectory |
Definition at line 76 of file trajectory.h.
|
inline |
Definition at line 285 of file trajectory.h.
|
inline |
Windup the trajectory so that continuous joints do not wrap.
| continuous | Which joints in each TrajectoryPoint are continuous. |
| trajectory | The trajectory to unwind. |
Definition at line 253 of file trajectory.h.