Aikido
Conversions.hpp
Go to the documentation of this file.
1 #ifndef AIKIDO_CONTROL_ROS_CONVERSIONS_HPP_
2 #define AIKIDO_CONTROL_ROS_CONVERSIONS_HPP_
3 
4 #include <memory>
5 
6 #include <sensor_msgs/JointState.h>
7 #include <trajectory_msgs/JointTrajectory.h>
8 
11 
12 namespace aikido {
13 namespace control {
14 namespace ros {
15 
22 std::unique_ptr<aikido::trajectory::Spline> toSplineJointTrajectory(
23  const std::shared_ptr<aikido::statespace::dart::MetaSkeletonStateSpace>&
24  space,
25  const trajectory_msgs::JointTrajectory& jointTrajectory);
26 
39 std::unique_ptr<aikido::trajectory::Spline> toSplineJointTrajectory(
40  const std::shared_ptr<aikido::statespace::dart::MetaSkeletonStateSpace>&
41  space,
42  const trajectory_msgs::JointTrajectory& jointTrajectory,
43  const Eigen::VectorXd& startPositions);
44 
49 trajectory_msgs::JointTrajectory toRosJointTrajectory(
50  const aikido::trajectory::ConstTrajectoryPtr& trajectory, double timestep);
51 
56 sensor_msgs::JointState positionsToJointState(
57  const Eigen::VectorXd& goalPositions,
58  const std::vector<std::string>& jointNames);
59 
60 } // namespace ros
61 } // namespace control
62 } // namespace aikido
63 
64 #endif // ifndef AIKIDO_CONTROL_ROS_CONVERSIONS_HPP_
aikido
Format of serialized trajectory in YAML.
Definition: algorithm.hpp:4
aikido::trajectory::ConstTrajectoryPtr
std::shared_ptr< const Trajectory > ConstTrajectoryPtr
Definition: Trajectory.hpp:13
Spline.hpp
aikido::control::ros::toRosJointTrajectory
trajectory_msgs::JointTrajectory toRosJointTrajectory(const aikido::trajectory::ConstTrajectoryPtr &trajectory, double timestep)
Converts Aikido Trajectory to ROS JointTrajectory.
aikido::control::ros::toSplineJointTrajectory
std::unique_ptr< aikido::trajectory::Spline > 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.
MetaSkeletonStateSpace.hpp
aikido::control::ros::positionsToJointState
sensor_msgs::JointState positionsToJointState(const Eigen::VectorXd &goalPositions, const std::vector< std::string > &jointNames)
Converts Eigen VectorXd and joint names to JointState.