Aikido
|
#include <memory>
#include <sensor_msgs/JointState.h>
#include <trajectory_msgs/JointTrajectory.h>
#include "aikido/statespace/dart/MetaSkeletonStateSpace.hpp"
#include "aikido/trajectory/Spline.hpp"
Go to the source code of this file.
Namespaces | |
aikido | |
Format of serialized trajectory in YAML. | |
aikido::control | |
aikido::control::ros | |
Functions | |
std::unique_ptr< aikido::trajectory::Spline > | aikido::control::ros::toSplineJointTrajectory (const std::shared_ptr< aikido::statespace::dart::MetaSkeletonStateSpace > &space, const trajectory_msgs::JointTrajectory &jointTrajectory) |
Converts a ROS JointTrajectory into an aikido's Spline trajectory. More... | |
std::unique_ptr< aikido::trajectory::Spline > | aikido::control::ros::toSplineJointTrajectory (const std::shared_ptr< aikido::statespace::dart::MetaSkeletonStateSpace > &space, const trajectory_msgs::JointTrajectory &jointTrajectory, const Eigen::VectorXd &startPositions) |
Converts a ROS JointTrajectory into an aikido's Spline trajectory. More... | |
trajectory_msgs::JointTrajectory | aikido::control::ros::toRosJointTrajectory (const aikido::trajectory::ConstTrajectoryPtr &trajectory, double timestep) |
Converts Aikido Trajectory to ROS JointTrajectory. More... | |
sensor_msgs::JointState | aikido::control::ros::positionsToJointState (const Eigen::VectorXd &goalPositions, const std::vector< std::string > &jointNames) |
Converts Eigen VectorXd and joint names to JointState. More... | |