Skip to content

Commit 2addcd5

Browse files
Update due to changes with tesseract environment getJointGroup and getKinematicGroup
1 parent f831e98 commit 2addcd5

File tree

3 files changed

+3
-3
lines changed

3 files changed

+3
-3
lines changed

trajopt/test/kinematic_costs_unit.cpp

Lines changed: 1 addition & 1 deletion
Original file line numberDiff line numberDiff line change
@@ -80,7 +80,7 @@ TEST_F(KinematicCostsTest, CartPoseJacCalculator) // NOLINT
8080
{
8181
CONSOLE_BRIDGE_logDebug("KinematicCostsTest, CartPoseJacCalculator");
8282

83-
const tesseract_kinematics::JointGroup::Ptr kin = env_->getJointGroup("right_arm");
83+
const tesseract_kinematics::JointGroup::ConstPtr kin = env_->getJointGroup("right_arm");
8484

8585
const std::string source_frame = env_->getRootLinkName();
8686
const std::string target_frame = "r_gripper_tool_frame";

trajopt_ifopt/test/cartesian_line_constraint_unit.cpp

Lines changed: 1 addition & 1 deletion
Original file line numberDiff line numberDiff line change
@@ -29,7 +29,7 @@ class CartesianLineConstraintUnit : public testing::TestWithParam<const char*>
2929
Environment::Ptr env = std::make_shared<Environment>();
3030
std::shared_ptr<ifopt::Composite> variables = std::make_shared<ifopt::Composite>("variable-sets", false);
3131

32-
tesseract_kinematics::JointGroup::Ptr manip;
32+
tesseract_kinematics::JointGroup::ConstPtr manip;
3333
CartLineInfo info;
3434
trajopt_ifopt::JointPosition::Ptr var;
3535

trajopt_ifopt/test/cartesian_position_constraint_unit.cpp

Lines changed: 1 addition & 1 deletion
Original file line numberDiff line numberDiff line change
@@ -58,7 +58,7 @@ class CartesianPositionConstraintUnit : public testing::TestWithParam<const char
5858
Environment::Ptr env = std::make_shared<Environment>();
5959
ifopt::Problem nlp;
6060

61-
tesseract_kinematics::JointGroup::Ptr kin_group;
61+
tesseract_kinematics::JointGroup::ConstPtr kin_group;
6262
CartPosConstraint::Ptr constraint;
6363

6464
Eigen::Index n_dof{ -1 };

0 commit comments

Comments
 (0)