|
kinematics-dynamics
|
The main, catch-all namespace for Robotics Lab UC3M.
Namespaces | |
| namespace | KdlVectorConverter |
| Collection of utilities related to KDL and std::vector classes. | |
| namespace | KinRepresentation |
| Collection of static methods to perform geometric transformations. | |
| namespace | test |
| Contains classes related to unit testing. | |
Classes | |
| class | AsibotConfiguration |
| Abstract base class for a robot configuration strategy selector. More... | |
| class | AsibotConfigurationFactory |
| Base factory class for AsibotConfiguration. More... | |
| class | AsibotConfigurationLeastOverallAngularDisplacement |
| IK solver configuration strategy selector based on the overall angle displacement of all joints. More... | |
| class | AsibotConfigurationLeastOverallAngularDisplacementFactory |
| Implementation factory class for AsibotConfigurationLeastOverallAngularDisplacement. More... | |
| class | CentroidTransform |
| class | ChainFkSolverPos_ST |
| FK solver using Screw Theory. More... | |
| class | ChainIkSolverPos_ID |
| IK solver using infinitesimal displacement twists. More... | |
| class | ChainIkSolverPos_ST |
| IK solver using Screw Theory. More... | |
| class | ConfigurationSelector |
| Abstract base class for a robot configuration strategy selector. More... | |
| class | ConfigurationSelectorFactory |
| Base factory class for ConfigurationSelector. More... | |
| class | ConfigurationSelectorHumanoidGait |
| IK solver configuration strategy selector based on human walking. More... | |
| class | ConfigurationSelectorHumanoidGaitFactory |
| Implementation factory class for ConfigurationSelectorHumanoidGait. More... | |
| class | ConfigurationSelectorLeastOverallAngularDisplacement |
| IK solver configuration strategy selector based on the overall displacement of all joints. More... | |
| class | ConfigurationSelectorLeastOverallAngularDisplacementFactory |
| Implementation factory class for ConfigurationSelectorLeastOverallAngularDisplacement. More... | |
| class | FtCompensation |
| Produces motion in the direction of an externally applied force measured by a force-torque sensor (pretty much mimicking a classical gravity compensation app). More... | |
| class | GrabberResponder |
| Callback class for dealing with incoming grabber data streams. More... | |
| class | HaarDetectionController |
| Create seek-and-follow trajectories based on Haar detection algorithms. More... | |
| class | ICartesianControl |
| Abstract base class for a cartesian controller. More... | |
| class | ICartesianSolver |
| Abstract base class for a cartesian solver. More... | |
| class | InvalidDevice |
| Represents an invalid device. More... | |
| class | KeyboardController |
| Sends streaming commands to the cartesian controller from a standard keyboard. More... | |
| class | LeapMotionSensorDevice |
| Represents a LeapMotion device wrapped as an analog sensor by YARP. More... | |
| class | LinearTrajectoryThread |
| Periodic thread that encapsulates a linear trajectory. More... | |
| class | MatrixExponential |
| Abstraction of a term in a product of exponentials (POE) formula. More... | |
| class | PadenKahanOne |
| First Paden-Kahan subproblem. More... | |
| class | PadenKahanThree |
| Third Paden-Kahan subproblem. More... | |
| class | PadenKahanTwo |
| Second Paden-Kahan subproblem. More... | |
| class | PardosGotorFour |
| Fourth Pardos-Gotor subproblem. More... | |
| class | PardosGotorOne |
| First Pardos-Gotor subproblem. More... | |
| class | PardosGotorThree |
| Third Pardos-Gotor subproblem. More... | |
| class | PardosGotorTwo |
| Second Pardos-Gotor subproblem. More... | |
| class | PoeExpression |
| Abstraction of a product of exponentials (POE) formula. More... | |
| class | RpcResponder |
| Responds to RPC command messages. More... | |
| class | RpcTransformResponder |
| Responds to RPC command messages, transforms incoming data. More... | |
| class | ScrewTheoryIkProblem |
| Proxy IK problem solver class that iterates over a sequence of subproblems. More... | |
| class | ScrewTheoryIkProblemBuilder |
| Automated IK solution finder. More... | |
| class | ScrewTheoryIkSubproblem |
| Interface shared by all IK subproblems found in Screw Theory applied to Robotics. More... | |
| class | SpnavSensorDevice |
| Represents a spacenav-compatible device, like the SpaceNavigator 6-DOF mouse from 3Dconnexion. More... | |
| class | StreamingDevice |
| Abstract class for a YARP streaming device. More... | |
| class | StreamingDeviceController |
| Sends streaming commands to the cartesian controller from a streaming input device like the 3Dconnexion Space Navigator. More... | |
| class | StreamingDeviceFactory |
| Factory class for creating instances of StreamingDevice. More... | |
| class | StreamResponder |
| Responds to streaming command messages. More... | |
| class | WiimoteDevice |
| Represents a Wiimote device wrapped as an analog sensor by YARP. More... | |
Functions | |
| KDL::Rotation | vectorPow2 (const KDL::Vector &v) |
| Multiply a vector by itself to obtain a square matrix. | |
| double | normalizeAngle (double angle) |
| Clip an angle value between certain bounds. | |
| double | toDeg (const double inRad) |
| double | toRad (const double inDeg) |
| void | xUpdateH (const yarp::sig::Vector &x, yarp::sig::Matrix &H) |
| yarp::sig::Matrix | rotX (const double &inDeg) |
| yarp::sig::Matrix | rotY (const double &inDeg) |
| yarp::sig::Matrix | rotZ (const double &inDeg) |
| yarp::sig::Matrix | eulerZYZtoH (const yarp::sig::Vector &x, const yarp::sig::Vector &o) |
| yarp::sig::Matrix | eulerYZtoH (const yarp::sig::Vector &x, const yarp::sig::Vector &o) |
| yarp::sig::Matrix | axisAngleToH (const yarp::sig::Vector &x, const yarp::sig::Vector &o) |
| yarp::sig::Matrix roboticslab::axisAngleToH | ( | const yarp::sig::Vector & | x, |
| const yarp::sig::Vector & | o | ||
| ) |
Thanks [Ugo Pattacini, Serena Ivaldi, Francesco Nori ((iCub ctrllib/math.h))] for axis2dcm().
| x | 3-vector in meters. |
| o | 4-vector in degrees. |
| yarp::sig::Matrix roboticslab::eulerYZtoH | ( | const yarp::sig::Vector & | x, |
| const yarp::sig::Vector & | o | ||
| ) |
Uses x to compute rot(Z).
| x | 3-vector in meters. |
| o | 2-vector in degrees. |
| yarp::sig::Matrix roboticslab::eulerZYZtoH | ( | const yarp::sig::Vector & | x, |
| const yarp::sig::Vector & | o | ||
| ) |
| x | 3-vector in meters. |
| o | 3-vector in degrees. |
| double roboticslab::toDeg | ( | const double | inRad | ) |
Simple function to pass from radians to degrees.
| inRad | angle value in radians. |
| double roboticslab::toRad | ( | const double | inDeg | ) |
Simple function to pass from degrees to radians.
| inDeg | angle value in degrees. |
| void roboticslab::xUpdateH | ( | const yarp::sig::Vector & | x, |
| yarp::sig::Matrix & | H | ||
| ) |
Update x values of an homogeneous matrix.
| x | 3-vector input. |
| H | homogeneous matrix (4x4) that will be modified. |