Go to the documentation of this file.
39 #include <gtest/gtest.h>
134 for (
unsigned i = 0; i < count; i++)
138 <<
" pos " <<
point->getVariablePosition(idx[0]) <<
" vel "
139 <<
point->getVariableVelocity(idx[0]) <<
" acc "
140 <<
point->getVariableAcceleration(idx[0]));
147 "jrk " << (
point->getVariableAcceleration(idx[0]) -
prev->getVariableAcceleration(idx[0])) /
153 TEST(TestCartesianSpeed, TestCartesianEndEffectorSpeed)
157 const char* end_effector_link =
"panda_link8";
164 Eigen::Isometry3d current_end_effector_state = kinematic_state->getGlobalLinkTransform(end_effector_link);
165 Eigen::Isometry3d next_end_effector_state;
166 double euclidean_distance = 0.0;
169 for (
size_t i = 0; i < num_waypoints - 1; i++)
172 next_end_effector_state = kinematic_state->getGlobalLinkTransform(end_effector_link);
173 euclidean_distance += (next_end_effector_state.translation() - current_end_effector_state.translation()).norm();
174 current_end_effector_state = next_end_effector_state;
177 ASSERT_NEAR(0.01, avg_speed, 2e-4);
181 for (
size_t i = 1; i < num_waypoints; i++)
184 ASSERT_NEAR(0.01, current_avg_speed, 2e-4);
188 int main(
int argc,
char** argv)
190 testing::InitGoogleTest(&argc, argv);
191 return RUN_ALL_TESTS();
robot_trajectory::RobotTrajectory TRAJECTORY(RMODEL, "panda_arm")
std::size_t getWayPointCount() const
const moveit::core::JointModelGroup * getGroup() const
const std::vector< int > & getVariableIndexList() const
Get the index locations in the complete robot state for all the variables in this group.
const moveit::core::RobotModelConstPtr & getRobotModel() const
moveit::core::RobotStatePtr & getFirstWayPointPtr()
RobotTrajectory & addSuffixWayPoint(const moveit::core::RobotState &state, double dt)
Add a point to the trajectory.
#define ROS_ERROR_NAMED(name,...)
Representation of a robot's state. This includes position, velocity, acceleration and effort.
Maintain a sequence of waypoints and the time durations between these waypoints.
double getWayPointDurationFromStart(std::size_t index) const
Returns the duration after start that a waypoint will be reached.
#define EXPECT_TRUE(args)
std::vector< double > WAYPOINT_DISTANCES
bool limitMaxCartesianLinkSpeed(robot_trajectory::RobotTrajectory &trajectory, const double speed, const moveit::core::LinkModel *link_model)
void printTrajectory(robot_trajectory::RobotTrajectory &trajectory)
void setVariablePosition(const std::string &variable, double value)
Set the position of a single variable. An exception is thrown if the variable name is not known.
int main(int argc, char **argv)
RobotTrajectory & clear()
TEST(TestCartesianSpeed, TestCartesianEndEffectorSpeed)
double getWayPointDurationFromPrevious(std::size_t index) const
std::chrono::system_clock::time_point point
bool computeTimeStamps(robot_trajectory::RobotTrajectory &trajectory, const double max_velocity_scaling_factor=1.0, const double max_acceleration_scaling_factor=1.0) const override
#define ROS_INFO_STREAM_NAMED(name, args)
moveit::core::RobotModelConstPtr RMODEL
moveit::core::RobotStatePtr & getWayPointPtr(std::size_t index)
bool initStraightTrajectory(robot_trajectory::RobotTrajectory &trajectory)
moveit::core::RobotModelPtr loadTestingRobotModel(const std::string &robot_name)
Loads a robot from moveit_resources.
moveit_core
Author(s): Ioan Sucan
, Sachin Chitta , Acorn Pooley
autogenerated on Sun Nov 3 2024 03:26:15