39#include <benchmark/benchmark.h>
52static void robotTrajectoryCreate(benchmark::State& st)
54 int n_states = st.range(0);
58 if (!robot_model->hasJointModelGroup(
TEST_GROUP))
60 st.SkipWithError(
"The planning group doesn't exist.");
63 auto* group = robot_model->getJointModelGroup(
TEST_GROUP);
71 auto trajectory = std::make_shared<robot_trajectory::RobotTrajectory>(robot_model, group);
72 for (
int i = 0; i < n_states; ++i)
75 const double joint_value = std::sin(0.001 * i);
76 const double duration_from_previous = 0.1;
79 Eigen::VectorXd joint_values = Eigen::VectorXd::Constant(group->getActiveVariableCount(), joint_value);
81 trajectory->addSuffixWayPoint(robot_state_waypoint, duration_from_previous);
87static void robotTrajectoryTiming(benchmark::State& st)
89 int n_states = st.range(0);
93 if (!robot_model->hasJointModelGroup(
TEST_GROUP))
95 st.SkipWithError(
"The planning group doesn't exist.");
98 auto* group = robot_model->getJointModelGroup(
TEST_GROUP);
102 robot_state.setToDefaultValues();
105 auto trajectory = std::make_shared<robot_trajectory::RobotTrajectory>(robot_model, group);
106 Eigen::VectorXd joint_values = Eigen::VectorXd::Zero(group->getActiveVariableCount());
107 for (
int i = 0; i < n_states; ++i)
110 const double joint_value = std::sin(0.001 * i);
111 const double duration_from_previous = 0.0;
114 joint_values = Eigen::VectorXd::Constant(group->getActiveVariableCount(), joint_value);
115 robot_state_waypoint.setJointGroupActivePositions(group, joint_values);
116 trajectory->addSuffixWayPoint(robot_state_waypoint, duration_from_previous);
120 std::unordered_map<std::string, double> velocity_limits, acceleration_limits;
121 for (
const auto& joint_name : group->getActiveJointModelNames())
123 velocity_limits[joint_name] = 1.0;
124 acceleration_limits[joint_name] = 2.0;
130 totg.computeTimeStamps(*trajectory, velocity_limits, acceleration_limits);
134BENCHMARK(robotTrajectoryCreate)->RangeMultiplier(10)->Range(10, 100000)->Unit(benchmark::kMillisecond);
135BENCHMARK(robotTrajectoryTiming)->RangeMultiplier(10)->Range(10, 20000)->Unit(benchmark::kMillisecond);
Representation of a robot's state. This includes position, velocity, acceleration and effort.
void setJointGroupActivePositions(const JointModelGroup *group, const std::vector< double > &gstate)
Given positions for the variables of active joints that make up a group, in the order found in the gr...
void setToDefaultValues()
Set all joints to their default positions. The default position is 0, or if that is not within bounds...
moveit::core::RobotModelPtr loadTestingRobotModel(const std::string &package_name, const std::string &urdf_relative_path, const std::string &srdf_relative_path)
Loads a robot model given a URDF and SRDF file in a package.
BENCHMARK(robotTrajectoryCreate) -> RangeMultiplier(10) ->Range(10, 100000) ->Unit(benchmark::kMillisecond)
constexpr char TEST_GROUP[]
constexpr char TEST_ROBOT[]