Skip to content

Commit 8d1c8ed

Browse files
committed
Add convenience function to transform trajectory into msg type
1 parent 2485c2e commit 8d1c8ed

File tree

2 files changed

+36
-0
lines changed

2 files changed

+36
-0
lines changed

moveit_core/trajectory_processing/include/moveit/trajectory_processing/time_optimal_trajectory_generation.h

+7
Original file line numberDiff line numberDiff line change
@@ -189,6 +189,13 @@ class Trajectory
189189
mutable std::list<TrajectoryStep>::const_iterator cached_trajectory_segment_;
190190
};
191191

192+
/**
193+
* @brief Converts a `trajectory_processing::Trajectory` into a `JointTrajectory` message with a given sampling rate.
194+
*/
195+
[[nodiscard]] trajectory_msgs::msg::JointTrajectory
196+
createTrajectoryMessage(const std::vector<std::string>& joint_names,
197+
const trajectory_processing::Trajectory& trajectory, const int sampling_rate);
198+
192199
MOVEIT_CLASS_FORWARD(TimeOptimalTrajectoryGeneration);
193200
class TimeOptimalTrajectoryGeneration : public TimeParameterization
194201
{

moveit_core/trajectory_processing/src/time_optimal_trajectory_generation.cpp

+29
Original file line numberDiff line numberDiff line change
@@ -1310,4 +1310,33 @@ double TimeOptimalTrajectoryGeneration::verifyScalingFactor(const double request
13101310
}
13111311
return scaling_factor;
13121312
}
1313+
1314+
trajectory_msgs::msg::JointTrajectory createTrajectoryMessage(const std::vector<std::string>& joint_names,
1315+
const trajectory_processing::Trajectory& trajectory,
1316+
const int sampling_rate)
1317+
{
1318+
trajectory_msgs::msg::JointTrajectory trajectory_msg;
1319+
trajectory_msg.joint_names = joint_names;
1320+
assert(sampling_rate > 0);
1321+
const double time_step = 1.0 / static_cast<double>(sampling_rate);
1322+
const int n_samples = static_cast<int>(trajectory.getDuration() / time_step) + 1;
1323+
trajectory_msg.points.reserve(n_samples);
1324+
for (int sample = 0; sample < n_samples; ++sample)
1325+
{
1326+
const double t = sample * time_step;
1327+
trajectory_msgs::msg::JointTrajectoryPoint point;
1328+
auto position = trajectory.getPosition(t);
1329+
auto velocity = trajectory.getVelocity(t);
1330+
auto acceleration = trajectory.getAcceleration(t);
1331+
for (std::size_t i = 0; i < joint_names.size(); i++)
1332+
{
1333+
point.positions.push_back(position[i]);
1334+
point.velocities.push_back(velocity[i]);
1335+
point.accelerations.push_back(acceleration[i]);
1336+
}
1337+
point.time_from_start = rclcpp::Duration(std::chrono::duration<double>(t));
1338+
trajectory_msg.points.push_back(std::move(point));
1339+
}
1340+
return trajectory_msg;
1341+
}
13131342
} // namespace trajectory_processing

0 commit comments

Comments
 (0)