1 #ifndef AIKIDO_CONTROL_ROS_CONVERSIONS_HPP_
2 #define AIKIDO_CONTROL_ROS_CONVERSIONS_HPP_
6 #include <sensor_msgs/JointState.h>
7 #include <trajectory_msgs/JointTrajectory.h>
23 const std::shared_ptr<aikido::statespace::dart::MetaSkeletonStateSpace>&
25 const trajectory_msgs::JointTrajectory& jointTrajectory);
40 const std::shared_ptr<aikido::statespace::dart::MetaSkeletonStateSpace>&
42 const trajectory_msgs::JointTrajectory& jointTrajectory,
43 const Eigen::VectorXd& startPositions);
57 const Eigen::VectorXd& goalPositions,
58 const std::vector<std::string>& jointNames);
64 #endif // ifndef AIKIDO_CONTROL_ROS_CONVERSIONS_HPP_