-
Notifications
You must be signed in to change notification settings - Fork 30
New issue
Have a question about this project? Sign up for a free GitHub account to open an issue and contact its maintainers and the community.
By clicking “Sign up for GitHub”, you agree to our terms of service and privacy statement. We’ll occasionally send you account related emails.
Already on GitHub? Sign in to your account
Function to convert trajectory_msgs::JointTrajectory into aikido::trajectory::Spline #147
Changes from 12 commits
43ea8bf
e3f783b
4391bf9
338f1b7
aafa1cf
a2e0ed8
22ba7b4
9e09781
6714011
785871b
c98e8ea
d4bdaa3
3a10630
064aa8a
8f1a94b
4fb24a5
File filter
Filter by extension
Conversations
Jump to
Diff view
Diff view
There are no files selected for viewing
Original file line number | Diff line number | Diff line change |
---|---|---|
@@ -0,0 +1,28 @@ | ||
#ifndef AIKIDO_CONTROL_ROS_CONVERSIONS_HPP_ | ||
#define AIKIDO_CONTROL_ROS_CONVERSIONS_HPP_ | ||
#include <memory> | ||
#include <trajectory_msgs/JointTrajectory.h> | ||
#include <aikido/statespace/dart/MetaSkeletonStateSpace.hpp> | ||
#include <aikido/trajectory/Spline.hpp> | ||
|
||
namespace aikido { | ||
namespace control { | ||
namespace ros { | ||
|
||
/// Converts a ROS JointTrajectory into an aikido's Spline trajectory. | ||
/// This method only handles single-DOF joints. | ||
/// \param[in] _space MetaSkeletonStateSpace for Spline trajectory. | ||
// Subspaces must be either 1D RnJoint or SO2Joint. | ||
/// \param[in] _jointTrajectory ROS JointTrajectory to be converted. | ||
/// \return Spline trajectory. | ||
std::unique_ptr<aikido::trajectory::Spline> convertJointTrajectory( | ||
const std::shared_ptr< | ||
aikido::statespace::dart::MetaSkeletonStateSpace>& space, | ||
const trajectory_msgs::JointTrajectory& jointTrajectory); | ||
|
||
} // namespace ros | ||
} // namespace control | ||
} // namespace aikido | ||
|
||
#endif // ifndef AIKIDO_CONTROL_ROS_CONVERSIONS_HPP_ | ||
|
Original file line number | Diff line number | Diff line change |
---|---|---|
@@ -0,0 +1,33 @@ | ||
#============================================================================== | ||
# Dependencies | ||
# | ||
find_package(trajectory_msgs QUIET) | ||
aikido_check_package(trajectory_msgs "aikido::control::ros" "trajectory_msgs") | ||
There was a problem hiding this comment. Choose a reason for hiding this commentThe reason will be displayed to describe this comment to others. Learn more. The
|
||
|
||
#============================================================================== | ||
# Libraries | ||
# | ||
set(sources | ||
Conversions.cpp | ||
) | ||
|
||
add_library("${PROJECT_NAME}_control_ros" SHARED ${sources}) | ||
target_include_directories("${PROJECT_NAME}_control_ros" SYSTEM | ||
PUBLIC | ||
${trajectory_msgs_INCLUDE_DIRS} | ||
) | ||
|
||
target_link_libraries("${PROJECT_NAME}_control_ros" | ||
"${PROJECT_NAME}_control" | ||
"${PROJECT_NAME}_statespace" | ||
"${PROJECT_NAME}_trajectory" | ||
${DART_LIBRARIES} | ||
${trajectory_msgs_LIBRARIES} | ||
) | ||
|
||
add_component(${PROJECT_NAME} control_ros) | ||
add_component_targets(${PROJECT_NAME} control_ros "${PROJECT_NAME}_control_ros") | ||
add_component_dependencies(${PROJECT_NAME} control_ros control statespace trajectory) | ||
|
||
coveralls_add_sources(${sources}) | ||
|
Original file line number | Diff line number | Diff line change |
---|---|---|
@@ -0,0 +1,288 @@ | ||
#include <sstream> | ||
#include <aikido/control/ros/Conversions.hpp> | ||
#include <aikido/statespace/dart/RnJoint.hpp> | ||
#include <aikido/statespace/dart/SO2Joint.hpp> | ||
#include <aikido/util/Spline.hpp> | ||
#include <dart/dynamics/Joint.hpp> | ||
#include <map> | ||
|
||
using aikido::statespace::dart::MetaSkeletonStateSpace; | ||
using SplineTrajectory = aikido::trajectory::Spline; | ||
using aikido::statespace::dart::RnJoint; | ||
using aikido::statespace::dart::SO2Joint; | ||
|
||
namespace aikido { | ||
namespace control { | ||
namespace ros { | ||
namespace { | ||
|
||
void reorder(std::map<size_t, size_t> indexMap, | ||
const Eigen::VectorXd& inVector, Eigen::VectorXd* outVector); | ||
|
||
//============================================================================= | ||
void checkVector( | ||
const std::string& _name, const std::vector<double>& _values, | ||
size_t _expectedLength, bool _isRequired, Eigen::VectorXd* _output) | ||
{ | ||
if (_values.empty()) | ||
{ | ||
if (_isRequired) | ||
{ | ||
std::stringstream message; | ||
message << _name << " are required."; | ||
throw std::invalid_argument{message.str()}; | ||
} | ||
} | ||
else if (_values.size() != _expectedLength) | ||
{ | ||
std::stringstream message; | ||
message << "Expected " << _name << " to be of length " << _expectedLength | ||
<< ", got " << _values.size() << "."; | ||
throw std::invalid_argument{message.str()}; | ||
} | ||
|
||
if (_output) | ||
*_output = Eigen::Map<const Eigen::VectorXd>(_values.data(), _values.size()); | ||
} | ||
|
||
//============================================================================= | ||
Eigen::MatrixXd fitPolynomial( | ||
double _currTime, | ||
const Eigen::VectorXd& _currPosition, | ||
const Eigen::VectorXd& _currVelocity, | ||
const Eigen::VectorXd& _currAcceleration, | ||
double _nextTime, | ||
const Eigen::VectorXd& _nextPosition, | ||
const Eigen::VectorXd& _nextVelocity, | ||
const Eigen::VectorXd& _nextAcceleration, | ||
size_t _numCoefficients) | ||
{ | ||
using aikido::util::SplineProblem; | ||
|
||
assert(_numCoefficients == 2 || _numCoefficients == 4 || _numCoefficients == 6); | ||
|
||
const auto numDofs = _currPosition.size(); | ||
SplineProblem<> splineProblem( | ||
Eigen::Vector2d(_currTime, _nextTime), _numCoefficients, numDofs); | ||
|
||
assert(_currPosition.size() == numDofs); | ||
assert(_nextPosition.size() == numDofs); | ||
splineProblem.addConstantConstraint(0, 0, _currPosition); | ||
splineProblem.addConstantConstraint(1, 0, _nextPosition); | ||
|
||
if (_numCoefficients >= 4) | ||
{ | ||
assert(_currVelocity.size() == numDofs); | ||
assert(_nextVelocity.size() == numDofs); | ||
splineProblem.addConstantConstraint(0, 1, _currVelocity); | ||
splineProblem.addConstantConstraint(1, 1, _nextVelocity); | ||
} | ||
|
||
if (_numCoefficients >= 6) | ||
{ | ||
assert(_currAcceleration.size() == numDofs); | ||
assert(_nextAcceleration.size() == numDofs); | ||
splineProblem.addConstantConstraint(0, 2, _currAcceleration); | ||
splineProblem.addConstantConstraint(1, 2, _nextAcceleration); | ||
} | ||
|
||
const auto splineSegment = splineProblem.fit(); | ||
return splineSegment.getCoefficients()[0]; | ||
} | ||
|
||
//============================================================================= | ||
void extractJointTrajectoryPoint( | ||
const trajectory_msgs::JointTrajectory& _trajectory, | ||
size_t _index, size_t _numDofs, | ||
Eigen::VectorXd* _positions, bool _positionsRequired, | ||
Eigen::VectorXd* _velocities, bool _velocitiesRequired, | ||
Eigen::VectorXd* _accelerations, bool _accelerationsRequired, | ||
std::map<size_t, size_t> indexMap) | ||
{ | ||
const auto& waypoint = _trajectory.points[_index]; | ||
|
||
try | ||
{ | ||
Eigen::VectorXd trajPos, trajVel, trajAccel; | ||
checkVector("positions", waypoint.positions, _numDofs, | ||
_positionsRequired, &trajPos); | ||
checkVector("velocities", waypoint.velocities, _numDofs, | ||
_velocitiesRequired, &trajVel); | ||
checkVector("accelerations", waypoint.accelerations, _numDofs, | ||
_accelerationsRequired, &trajAccel); | ||
|
||
if ( trajPos.size() > 0 ) | ||
reorder(indexMap, trajPos, _positions); | ||
if ( trajVel.size() > 0 ) | ||
reorder(indexMap, trajVel, _velocities); | ||
if ( trajAccel.size() > 0 ) | ||
reorder(indexMap, trajAccel, _accelerations); | ||
} | ||
catch (const std::invalid_argument& e) | ||
{ | ||
std::stringstream message; | ||
message << "Waypoint " << _index << " is invalid: " << e.what(); | ||
throw std::invalid_argument(message.str()); | ||
} | ||
} | ||
|
||
//============================================================================= | ||
// The rows of inVector is reordered in outVector. | ||
void reorder(std::map<size_t, size_t> indexMap, | ||
const Eigen::VectorXd& inVector, Eigen::VectorXd* outVector) | ||
{ | ||
*outVector = Eigen::VectorXd::Zero(inVector.size()); | ||
for (auto it = indexMap.begin(); it != indexMap.end(); ++it) | ||
{ | ||
(*outVector)(it->second) = inVector(it->first); | ||
} | ||
} | ||
|
||
//============================================================================= | ||
dart::dynamics::Joint* findJointByName( | ||
dart::dynamics::MetaSkeleton* metaSkeleton, const std::string& jointName) | ||
There was a problem hiding this comment. Choose a reason for hiding this commentThe reason will be displayed to describe this comment to others. Learn more. Nit: There was a problem hiding this comment. Choose a reason for hiding this commentThe reason will be displayed to describe this comment to others. Learn more. Hm, I know polymorphisms work both for pointers and references, but I thought our convention is to take a const pointer. There was a problem hiding this comment. Choose a reason for hiding this commentThe reason will be displayed to describe this comment to others. Learn more. The convention I've seen (and generally follow) is to prefer references and only use pointers for: (1) output parameters or (2) optional parameters that may be @psigen Want to break the tie? 😬 There was a problem hiding this comment. Choose a reason for hiding this commentThe reason will be displayed to describe this comment to others. Learn more. I haven't decided my preference here yet. If we want to use references for this case, then I see there are tons of changes in Aikido code base we need to make for the consistency. Just saying. 😅 There was a problem hiding this comment. Choose a reason for hiding this commentThe reason will be displayed to describe this comment to others. Learn more. Are you sure? Note that |
||
{ | ||
for (size_t i = 0; i < metaSkeleton->getNumJoints(); ++i) | ||
{ | ||
if (metaSkeleton->getJoint(i)->getName() == jointName) | ||
return metaSkeleton->getJoint(i); | ||
} | ||
There was a problem hiding this comment. Choose a reason for hiding this commentThe reason will be displayed to describe this comment to others. Learn more. Check if the There was a problem hiding this comment. Choose a reason for hiding this commentThe reason will be displayed to describe this comment to others. Learn more. As a note, I'm thinking of implementing this to There was a problem hiding this comment. Choose a reason for hiding this commentThe reason will be displayed to describe this comment to others. Learn more. @jslee02 That would be a great addition. 👍 In fact, it would be nice to have two functions: (1) one that returns a list of joints and (2) one that returns a single joint and prints a warning [or returns In any case, I don't want to wait on a new version of DART before merging this pull request. So we should also implement it here. 😉 There was a problem hiding this comment. Choose a reason for hiding this commentThe reason will be displayed to describe this comment to others. Learn more. There was a problem hiding this comment. Choose a reason for hiding this commentThe reason will be displayed to describe this comment to others. Learn more. Thanks @jslee02! |
||
|
||
return nullptr; | ||
} | ||
|
||
} // namespace | ||
There was a problem hiding this comment. Choose a reason for hiding this commentThe reason will be displayed to describe this comment to others. Learn more. I suspect that using a permutation matrix here will be a lot slower than operating directly on the list of Since this is an entirely an implementation detail, I am fine keeping it as it is for now. However, we may want to consider refactoring this in the future if performance becomes an issue. |
||
|
||
//============================================================================= | ||
std::unique_ptr<SplineTrajectory> convertJointTrajectory( | ||
const std::shared_ptr<MetaSkeletonStateSpace>& space, | ||
const trajectory_msgs::JointTrajectory& jointTrajectory) | ||
{ | ||
if (!space) | ||
throw std::invalid_argument{"StateSpace must be non-null."}; | ||
|
||
const auto numControlledJoints = space->getNumSubspaces(); | ||
if (jointTrajectory.joint_names.size() != numControlledJoints) | ||
{ | ||
std::stringstream message; | ||
message << "Incorrect number of joints: expected " | ||
<< numControlledJoints << ", got " | ||
<< jointTrajectory.joint_names.size() << "."; | ||
throw std::invalid_argument{message.str()}; | ||
} | ||
|
||
// Check that all joints are single DOF. | ||
There was a problem hiding this comment. Choose a reason for hiding this commentThe reason will be displayed to describe this comment to others. Learn more. Nit: "...RnJoint or SO2Joint state spaces." |
||
for (size_t i = 0; i < space->getNumSubspaces(); ++i) | ||
{ | ||
auto joint = space->getJointSpace(i)->getJoint(); | ||
auto jointSpace = space->getSubspace(i); | ||
auto rnJoint = dynamic_cast<RnJoint*>(jointSpace.get()); | ||
auto so2Joint = dynamic_cast<SO2Joint*>(jointSpace.get()); | ||
|
||
if (joint->getNumDofs() != 1 || (!rnJoint && !so2Joint)) | ||
{ | ||
std::stringstream message; | ||
message << "Only single-DOF RnJoint and SO2Joint are supported. Joint " | ||
<< joint->getName() << "(index: " << i << ") is a " | ||
<< joint->getType() << " with " | ||
<< joint->getNumDofs() << " DOFs."; | ||
throw std::invalid_argument{message.str()}; | ||
} | ||
There was a problem hiding this comment. Choose a reason for hiding this commentThe reason will be displayed to describe this comment to others. Learn more. Check that |
||
} | ||
|
||
if (jointTrajectory.points.size() < 2) | ||
{ | ||
throw std::invalid_argument{ | ||
"Trajectory must contain two or more waypoints."}; | ||
} | ||
|
||
// Map joint indices between jointTrajectory and space subspaces. | ||
std::map<size_t, size_t> rosJointToMetaSkeletonJoint; | ||
|
||
auto metaSkeleton = space->getMetaSkeleton(); | ||
|
||
for (size_t i = 0; i < jointTrajectory.joint_names.size(); ++i) | ||
{ | ||
std::string jointName = jointTrajectory.joint_names[i]; | ||
There was a problem hiding this comment. Choose a reason for hiding this commentThe reason will be displayed to describe this comment to others. Learn more. Nit: |
||
auto joint = findJointByName(metaSkeleton.get(), jointName); | ||
|
||
if (!joint) | ||
{ | ||
std::stringstream message; | ||
message << "Joint " << jointName << " (index: " << i << ")" | ||
<< " does not exist in metaSkeleton."; | ||
There was a problem hiding this comment. Choose a reason for hiding this commentThe reason will be displayed to describe this comment to others. Learn more. Nit: This index is ambiguous because it could refer to an index in the |
||
throw std::invalid_argument{message.str()}; | ||
} | ||
auto index = metaSkeleton->getIndexOf(joint); | ||
assert(index != dart::dynamics::INVALID_INDEX); | ||
|
||
rosJointToMetaSkeletonJoint.emplace(std::make_pair(i, index)); | ||
There was a problem hiding this comment. Choose a reason for hiding this commentThe reason will be displayed to describe this comment to others. Learn more. Verify that this is not a duplicate, i.e. that Nit: Also, it would be nice to more descriptive variable names than |
||
|
||
} | ||
There was a problem hiding this comment. Choose a reason for hiding this commentThe reason will be displayed to describe this comment to others. Learn more. This check will fail if Also, add a check that throws an exception if any of the joints are not single DOF. There was a problem hiding this comment. Choose a reason for hiding this commentThe reason will be displayed to describe this comment to others. Learn more. @mkoval I am a bit confused about your first comment. If we can't assume that they are given in the same order, how do we build the initial mapping? Should we compare each One more question: is it joint_name or dof_name that we get from There was a problem hiding this comment. Choose a reason for hiding this commentThe reason will be displayed to describe this comment to others. Learn more.
That was my idea. None of these solutions are perfect, but I trust the names to be correct more than I trust the indices to be.
There is no correct answer here, since the
They are not guaranteed to be the same in DART, but I believe they are by default. @jslee02 Is that correct? |
||
|
||
// Extract the first waypoint to infer the dimensionality of the trajectory. | ||
Eigen::VectorXd currPosition, currVelocity, currAcceleration; | ||
extractJointTrajectoryPoint(jointTrajectory, 0, numControlledJoints, | ||
&currPosition, true, &currVelocity, false, &currAcceleration, false, | ||
rosJointToMetaSkeletonJoint); | ||
|
||
const auto& firstWaypoint = jointTrajectory.points.front(); | ||
auto currTimeFromStart = firstWaypoint.time_from_start.toSec(); | ||
|
||
const auto isPositionRequired = true; | ||
const auto isVelocityRequired = (currVelocity.size() != 0); | ||
const auto isAccelerationRequired = (currAcceleration.size() != 0); | ||
if (isAccelerationRequired && !isVelocityRequired) | ||
{ | ||
throw std::invalid_argument{ | ||
"Velocity is required since acceleration is specified."}; | ||
} | ||
|
||
int numCoefficients; | ||
if (isAccelerationRequired) | ||
numCoefficients = 6; // quintic | ||
else if (isVelocityRequired) | ||
numCoefficients = 4; // cubic | ||
else | ||
numCoefficients = 2; // linear | ||
|
||
// Convert the ROS trajectory message to an Aikido spline. | ||
std::unique_ptr<SplineTrajectory> trajectory{new SplineTrajectory{space}}; | ||
auto currState = space->createState(); | ||
|
||
const auto& waypoints = jointTrajectory.points; | ||
for (size_t iwaypoint = 1; iwaypoint < waypoints.size(); ++iwaypoint) | ||
{ | ||
Eigen::VectorXd nextPosition, nextVelocity, nextAcceleration; | ||
extractJointTrajectoryPoint(jointTrajectory, iwaypoint, numControlledJoints, | ||
&nextPosition, isPositionRequired, | ||
&nextVelocity, isVelocityRequired, | ||
&nextAcceleration, isAccelerationRequired, | ||
rosJointToMetaSkeletonJoint); | ||
|
||
// Compute spline coefficients for this polynomial segment. | ||
const auto nextTimeFromStart = waypoints[iwaypoint].time_from_start.toSec(); | ||
const auto segmentDuration = nextTimeFromStart - currTimeFromStart; | ||
const auto segmentCoefficients = fitPolynomial( | ||
0., Eigen::VectorXd::Zero(numControlledJoints), currVelocity, currAcceleration, | ||
segmentDuration, nextPosition - currPosition, nextVelocity, nextAcceleration, | ||
numCoefficients); | ||
|
||
// Add a segment to the trajectory. | ||
space->convertPositionsToState(currPosition, currState); | ||
trajectory->addSegment(segmentCoefficients, segmentDuration, currState); | ||
|
||
// Advance to the next segment. | ||
currPosition = nextPosition; | ||
currVelocity = nextVelocity; | ||
currAcceleration = nextAcceleration; | ||
currTimeFromStart = nextTimeFromStart; | ||
} | ||
|
||
return std::move(trajectory); | ||
} | ||
|
||
} // namespace ros | ||
} // namespace control | ||
} // namespace aikido | ||
|
Original file line number | Diff line number | Diff line change |
---|---|---|
@@ -1,24 +1,22 @@ | ||
aikido_add_test(test_KinematicSimulationTrajectoryExecutor | ||
test_KinematicSimulationTrajectoryExecutor.cpp) | ||
|
||
target_link_libraries(test_KinematicSimulationTrajectoryExecutor | ||
"${PROJECT_NAME}_control") | ||
|
||
aikido_add_test(test_BarrettFingerSpreadCommandExecutor | ||
test_BarrettFingerSpreadCommandExecutor.cpp) | ||
|
||
target_link_libraries(test_BarrettFingerSpreadCommandExecutor | ||
"${PROJECT_NAME}_control") | ||
|
||
|
||
aikido_add_test(test_BarrettFingerPositionCommandExecutor | ||
test_BarrettFingerPositionCommandExecutor.cpp) | ||
|
||
target_link_libraries(test_BarrettFingerPositionCommandExecutor | ||
"${PROJECT_NAME}_control") | ||
|
||
aikido_add_test(test_BarrettHandPositionCommandExecutor | ||
test_BarrettHandPositionCommandExecutor.cpp) | ||
|
||
target_link_libraries(test_BarrettHandPositionCommandExecutor | ||
"${PROJECT_NAME}_control") | ||
|
||
add_subdirectory("ros") | ||
|
Original file line number | Diff line number | Diff line change |
---|---|---|
@@ -0,0 +1,7 @@ | ||
if(TARGET "${PROJECT_NAME}_control_ros") | ||
aikido_add_test(test_Conversions | ||
test_Conversions.cpp) | ||
target_link_libraries(test_Conversions | ||
"${PROJECT_NAME}_control_ros") | ||
endif() | ||
|
There was a problem hiding this comment.
Choose a reason for hiding this comment
The reason will be displayed to describe this comment to others. Learn more.
Nits:
Rn
andSO2
joints.