Skip to content

Commit

Permalink
Remove old deprecated functions (moveit#2384)
Browse files Browse the repository at this point in the history
  • Loading branch information
rmessaou authored and m-elwin committed Dec 4, 2023
1 parent f7d8802 commit cd84de7
Show file tree
Hide file tree
Showing 18 changed files with 4 additions and 344 deletions.
Expand Up @@ -188,9 +188,6 @@ class DistanceField
*/
void addShapeToField(const shapes::Shape* shape, const Eigen::Isometry3d& pose);

// DEPRECATED form
[[deprecated]] void addShapeToField(const shapes::Shape* shape, const geometry_msgs::msg::Pose& pose);

/**
* \brief Adds an octree to the distance field. Cells that are
* occupied in the octree that lie within the voxel grid are added
Expand Down Expand Up @@ -227,10 +224,6 @@ class DistanceField
void moveShapeInField(const shapes::Shape* shape, const Eigen::Isometry3d& old_pose,
const Eigen::Isometry3d& new_pose);

// DEPRECATED form
[[deprecated]] void moveShapeInField(const shapes::Shape* shape, const geometry_msgs::msg::Pose& old_pose,
const geometry_msgs::msg::Pose& new_pose);

/**
* \brief All points corresponding to the shape are removed from the
* distance field.
Expand All @@ -242,9 +235,6 @@ class DistanceField
*/
void removeShapeFromField(const shapes::Shape* shape, const Eigen::Isometry3d& pose);

// DEPRECATED form
[[deprecated]] void removeShapeFromField(const shapes::Shape* shape, const geometry_msgs::msg::Pose& pose);

/**
* \brief Resets all points in the distance field to an uninitialize
* value.
Expand Down
Expand Up @@ -202,9 +202,6 @@ class VoxelGrid
*/
double getResolution() const;

/** \brief deprecated. Use the version with no arguments. */
double getResolution(Dimension dim) const;

/**
* \brief Gets the origin (minimum point) of the indicated dimension
*
Expand Down Expand Up @@ -440,12 +437,6 @@ inline double VoxelGrid<T>::getResolution() const
return resolution_;
}

template <typename T>
inline double VoxelGrid<T>::getResolution(Dimension /*dim*/) const
{
return resolution_;
}

template <typename T>
inline double VoxelGrid<T>::getOrigin(Dimension dim) const
{
Expand Down
26 changes: 0 additions & 26 deletions moveit_core/distance_field/src/distance_field.cpp
Expand Up @@ -231,14 +231,6 @@ void DistanceField::addShapeToField(const shapes::Shape* shape, const Eigen::Iso
addPointsToField(point_vec);
}

// DEPRECATED
void DistanceField::addShapeToField(const shapes::Shape* shape, const geometry_msgs::msg::Pose& pose)
{
Eigen::Isometry3d pose_e;
tf2::fromMsg(pose, pose_e);
addShapeToField(shape, pose_e);
}

void DistanceField::getOcTreePoints(const octomap::OcTree* octree, EigenSTL::vector_Vector3d* points)
{
// lower extent
Expand Down Expand Up @@ -313,16 +305,6 @@ void DistanceField::moveShapeInField(const shapes::Shape* shape, const Eigen::Is
updatePointsInField(old_point_vec, new_point_vec);
}

// DEPRECATED
void DistanceField::moveShapeInField(const shapes::Shape* shape, const geometry_msgs::msg::Pose& old_pose,
const geometry_msgs::msg::Pose& new_pose)
{
Eigen::Isometry3d old_pose_e, new_pose_e;
tf2::fromMsg(old_pose, old_pose_e);
tf2::fromMsg(new_pose, new_pose_e);
moveShapeInField(shape, old_pose_e, new_pose_e);
}

void DistanceField::removeShapeFromField(const shapes::Shape* shape, const Eigen::Isometry3d& pose)
{
bodies::Body* body = bodies::createEmptyBodyFromShapeType(shape->type);
Expand All @@ -335,14 +317,6 @@ void DistanceField::removeShapeFromField(const shapes::Shape* shape, const Eigen
removePointsFromField(point_vec);
}

// DEPRECATED
void DistanceField::removeShapeFromField(const shapes::Shape* shape, const geometry_msgs::msg::Pose& pose)
{
Eigen::Isometry3d pose_e;
tf2::fromMsg(pose, pose_e);
removeShapeFromField(shape, pose_e);
}

void DistanceField::getPlaneMarkers(PlaneVisualizationType type, double length, double width, double height,
const Eigen::Vector3d& origin, const std::string& frame_id,
const rclcpp::Time& stamp, visualization_msgs::msg::Marker& plane_marker) const
Expand Down
Expand Up @@ -592,51 +592,6 @@ class MOVEIT_KINEMATICS_BASE_EXPORT KinematicsBase
std::map<int, double> redundant_joint_discretization_;
std::vector<DiscretizationMethod> supported_methods_;

/**
* @brief Enables kinematics plugins access to parameters that are defined
* for the private namespace and inside 'robot_description_kinematics'.
* Parameters are searched in the following locations and order
*
* ~/<group_name>/<param>
* ~/<param>
* robot_description_kinematics/<group_name>/<param>
* robot_description_kinematics/<param>
*
* This order maintains default behavior by keeping the private namespace
* as the predominant configuration but also allows groupwise specifications.
*/
template <typename T>
[[deprecated("Use generate_parameter_library instead")]] inline bool
lookupParam(const rclcpp::Node::SharedPtr& node, const std::string& param, T& val, const T& default_val) const
{
if (node->has_parameter({ group_name_ + "." + param }))
{
node->get_parameter(group_name_ + "." + param, val);
return true;
}

if (node->has_parameter({ param }))
{
node->get_parameter(param, val);
return true;
}

if (node->has_parameter({ "robot_description_kinematics." + group_name_ + "." + param }))
{
node->get_parameter("robot_description_kinematics." + group_name_ + "." + param, val);
return true;
}

if (node->has_parameter("robot_description_kinematics." + param))
{
node->get_parameter("robot_description_kinematics." + param, val);
return true;
}

val = default_val;
return false;
}

/** Store some core variables passed via initialize().
*
* @param robot_model RobotModel, this kinematics solver should act on.
Expand Down
Expand Up @@ -925,20 +925,6 @@ class MOVEIT_PLANNING_SCENE_EXPORT PlanningScene : public std::enable_shared_fro
/** \brief Outputs debug information about the planning scene contents */
void printKnownObjects(std::ostream& out = std::cout) const;

/** \brief Check if a message includes any information about a planning scene, or it is just a default, empty message.
*/
[[deprecated("Use moveit/utils/message_checks.h instead")]] static bool
isEmpty(const moveit_msgs::msg::PlanningScene& msg);

/** \brief Check if a message includes any information about a planning scene world, or it is just a default, empty
* message. */
[[deprecated("Use moveit/utils/message_checks.h instead")]] static bool
isEmpty(const moveit_msgs::msg::PlanningSceneWorld& msg);

/** \brief Check if a message includes any information about a robot state, or it is just a default, empty message. */
[[deprecated("Use moveit/utils/message_checks.h instead")]] static bool
isEmpty(const moveit_msgs::msg::RobotState& msg);

/** \brief Clone a planning scene. Even if the scene \e scene depends on a parent, the cloned scene will not. */
static PlanningScenePtr clone(const PlanningSceneConstPtr& scene);

Expand Down
15 changes: 0 additions & 15 deletions moveit_core/planning_scene/src/planning_scene.cpp
Expand Up @@ -144,21 +144,6 @@ class SceneTransforms : public moveit::core::Transforms
const PlanningScene* scene_;
};

bool PlanningScene::isEmpty(const moveit_msgs::msg::PlanningScene& msg)
{
return moveit::core::isEmpty(msg);
}

bool PlanningScene::isEmpty(const moveit_msgs::msg::RobotState& msg)
{
return moveit::core::isEmpty(msg);
}

bool PlanningScene::isEmpty(const moveit_msgs::msg::PlanningSceneWorld& msg)
{
return moveit::core::isEmpty(msg);
}

PlanningScene::PlanningScene(const moveit::core::RobotModelConstPtr& robot_model,
const collision_detection::WorldPtr& world)

Expand Down
Expand Up @@ -133,14 +133,6 @@ class AttachedBody
return shape_poses_in_link_frame_;
}

/** \brief Get the fixed transforms (the transforms to the shapes of this body, relative to the link). The returned
* transforms are guaranteed to be valid isometries.
* Deprecated. Use getShapePosesInLinkFrame instead. */
[[deprecated]] const EigenSTL::vector_Isometry3d& getFixedTransforms() const
{
return shape_poses_in_link_frame_;
}

/** \brief Get subframes of this object (relative to the object pose). The returned transforms are guaranteed to be
* valid isometries. */
const moveit::core::FixedTransformsMap& getSubframes() const
Expand Down
108 changes: 0 additions & 108 deletions moveit_core/robot_state/include/moveit/robot_state/robot_state.h
Expand Up @@ -1067,78 +1067,6 @@ class RobotState
bool setFromDiffIK(const JointModelGroup* group, const geometry_msgs::msg::Twist& twist, const std::string& tip,
double dt, const GroupStateValidityCallbackFn& constraint = GroupStateValidityCallbackFn());

/** \brief Compute the sequence of joint values that correspond to a straight Cartesian path for a particular group.
The Cartesian path to be followed is specified as a direction of motion (\e direction, unit vector) for the origin
The Cartesian path to be followed is specified as a direction of motion (\e direction, unit vector) for the origin
of a robot link (\e link). The direction is assumed to be either in a global reference frame or in the local
reference frame of the link. In the latter case (\e global_reference_frame is false) the \e direction is rotated
accordingly. The link needs to move in a straight line, following the specified direction, for the desired \e
distance. The resulting joint values are stored in the vector \e traj, one by one. The maximum distance in
Cartesian space between consecutive points on the resulting path is specified in the \e MaxEEFStep struct which
provides two fields: translation and rotation. If a \e validCallback is specified, this is passed to the internal
call to setFromIK(). In case of IK failure, the computation of the path stops and the value returned corresponds to
the distance that was computed and for which corresponding states were added to the path. At the end of the
function call, the state of the group corresponds to the last attempted Cartesian pose.
During the computation of the trajectory, it is usually preferred if consecutive joint values do not 'jump' by a
large amount in joint space, even if the Cartesian distance between the corresponding points is small as expected.
To account for this, the \e jump_threshold struct is provided, which comprises three fields:
\e jump_threshold_factor, \e revolute_jump_threshold and \e prismatic_jump_threshold.
If either \e revolute_jump_threshold or \e prismatic_jump_threshold are non-zero, we test for absolute jumps.
If \e jump_threshold_factor is non-zero, we test for relative jumps. Otherwise (all params are zero), jump
detection is disabled.
For relative jump detection, the average joint-space distance between consecutive points in the trajectory is
computed. If any individual joint-space motion delta is larger then this average distance by a factor of
\e jump_threshold_factor, this step is considered a failure and the returned path is truncated up to just
before the jump.
For absolute jump thresholds, if any individual joint-space motion delta is larger then \e revolute_jump_threshold
for revolute joints or \e prismatic_jump_threshold for prismatic joints then this step is considered a failure and
the returned path is truncated up to just before the jump.
NOTE: As of ROS-Melodic these are deprecated and should not be used
*/
[[deprecated]] double
computeCartesianPath(const JointModelGroup* group, std::vector<RobotStatePtr>& traj, const LinkModel* link,
const Eigen::Vector3d& direction, bool global_reference_frame, double distance, double max_step,
double jump_threshold_factor,
const GroupStateValidityCallbackFn& validCallback = GroupStateValidityCallbackFn(),
const kinematics::KinematicsQueryOptions& options = kinematics::KinematicsQueryOptions());

/** \brief Compute the sequence of joint values that correspond to a straight Cartesian path, for a particular group.
In contrast to the previous function, the Cartesian path is specified as a target frame to be reached (\e target)
for the origin of a robot link (\e link). The target frame is assumed to be either in a global reference frame or
in the local reference frame of the link. In the latter case (\e global_reference_frame is false) the \e target is
rotated accordingly. All other comments from the previous function apply.
NOTE: As of ROS-Melodic these are deprecated and should not be used
*/
[[deprecated]] double
computeCartesianPath(const JointModelGroup* group, std::vector<RobotStatePtr>& traj, const LinkModel* link,
const Eigen::Isometry3d& target, bool global_reference_frame, double max_step,
double jump_threshold_factor,
const GroupStateValidityCallbackFn& validCallback = GroupStateValidityCallbackFn(),
const kinematics::KinematicsQueryOptions& options = kinematics::KinematicsQueryOptions());

/** \brief Compute the sequence of joint values that perform a general Cartesian path.
In contrast to the previous functions, the Cartesian path is specified as a set of \e waypoints to be sequentially
reached for the origin of a robot link (\e link). The waypoints are transforms given either in a global reference
frame or in the local reference frame of the link at the immediately preceding waypoint. The link needs to move
in a straight line between two consecutive waypoints. All other comments apply.
NOTE: As of ROS-Melodic these are deprecated and should not be used
*/
[[deprecated]] double
computeCartesianPath(const JointModelGroup* group, std::vector<RobotStatePtr>& traj, const LinkModel* link,
const EigenSTL::vector_Isometry3d& waypoints, bool global_reference_frame, double max_step,
double jump_threshold_factor,
const GroupStateValidityCallbackFn& validCallback = GroupStateValidityCallbackFn(),
const kinematics::KinematicsQueryOptions& options = kinematics::KinematicsQueryOptions());

/** \brief Compute the Jacobian with reference to a particular point on a given link, for a specified group.
* \param group The group to compute the Jacobian for
* \param link The link model to compute the Jacobian for
Expand Down Expand Up @@ -1599,27 +1527,6 @@ class RobotState
**/
void attachBody(std::unique_ptr<AttachedBody> attached_body);

/** \brief Add an attached body to this state. Ownership of the
* memory for the attached body is assumed by the state.
*
* This only adds the given body to this RobotState
* instance. It does not change anything about other
* representations of the object elsewhere in the system. So if the
* body represents an object in a collision_detection::World (like
* from a planning_scene::PlanningScene), you will likely need to remove the
* corresponding object from that world to avoid having collisions
* detected against it.
*
* \note This version of the function (taking an AttachedBody
* pointer) does not copy the AttachedBody object, it just uses it
* directly. The AttachedBody object stores its position data
* internally. This means you should <b>never attach a single
* AttachedBody instance to multiple RobotState instances</b>, or
* the body positions will get corrupted. You need to make a fresh
* copy of the AttachedBody object for each RobotState you attach it
* to.*/
[[deprecated("Deprecated. Pass a unique_ptr instead")]] void attachBody(AttachedBody* attached_body);

/** @brief Add an attached body to a link
* @param id The string id associated with the attached body
* @param pose The pose associated with the attached body
Expand Down Expand Up @@ -1857,21 +1764,6 @@ class RobotState
}
}

/** \brief Update a set of joints that are certain to be mimicking other joints */
/* use updateMimicJoints() instead, which also marks joints dirty */
[[deprecated]] void updateMimicJoint(const std::vector<const JointModel*>& mim)
{
for (const JointModel* jm : mim)
{
const int fvi = jm->getFirstVariableIndex();
position_[fvi] = jm->getMimicFactor() * position_[jm->getMimic()->getFirstVariableIndex()] + jm->getMimicOffset();
// Only mark joint transform dirty, but not the associated link transform
// as this function is always used in combination of
// updateMimicJoint(group->getMimicJointModels()) + markDirtyJointTransforms(group);
dirty_joint_transforms_[jm->getJointIndex()] = 1;
}
}

/** \brief Update all mimic joints within group */
void updateMimicJoints(const JointModelGroup* group)
{
Expand Down
38 changes: 0 additions & 38 deletions moveit_core/robot_state/src/robot_state.cpp
Expand Up @@ -1057,11 +1057,6 @@ void RobotState::attachBody(std::unique_ptr<AttachedBody> attached_body)
attached_body_map_[attached_body->getName()] = std::move(attached_body);
}

void RobotState::attachBody(AttachedBody* attached_body)
{
attachBody(std::unique_ptr<AttachedBody>(attached_body));
}

void RobotState::attachBody(const std::string& id, const Eigen::Isometry3d& pose,
const std::vector<shapes::ShapeConstPtr>& shapes,
const EigenSTL::vector_Isometry3d& shape_poses, const std::set<std::string>& touch_links,
Expand Down Expand Up @@ -2098,39 +2093,6 @@ bool RobotState::setFromIKSubgroups(const JointModelGroup* jmg, const EigenSTL::
return false;
}

double RobotState::computeCartesianPath(const JointModelGroup* group, std::vector<RobotStatePtr>& traj,
const LinkModel* link, const Eigen::Vector3d& direction,
bool global_reference_frame, double distance, double max_step,
double jump_threshold_factor, const GroupStateValidityCallbackFn& validCallback,
const kinematics::KinematicsQueryOptions& options)
{
return CartesianInterpolator::computeCartesianPath(this, group, traj, link, direction, global_reference_frame,
distance, MaxEEFStep(max_step),
JumpThreshold(jump_threshold_factor), validCallback, options);
}

double RobotState::computeCartesianPath(const JointModelGroup* group, std::vector<RobotStatePtr>& traj,
const LinkModel* link, const Eigen::Isometry3d& target,
bool global_reference_frame, double max_step, double jump_threshold_factor,
const GroupStateValidityCallbackFn& validCallback,
const kinematics::KinematicsQueryOptions& options)
{
return CartesianInterpolator::computeCartesianPath(this, group, traj, link, target, global_reference_frame,
MaxEEFStep(max_step), JumpThreshold(jump_threshold_factor),
validCallback, options);
}

double RobotState::computeCartesianPath(const JointModelGroup* group, std::vector<RobotStatePtr>& traj,
const LinkModel* link, const EigenSTL::vector_Isometry3d& waypoints,
bool global_reference_frame, double max_step, double jump_threshold_factor,
const GroupStateValidityCallbackFn& validCallback,
const kinematics::KinematicsQueryOptions& options)
{
return CartesianInterpolator::computeCartesianPath(this, group, traj, link, waypoints, global_reference_frame,
MaxEEFStep(max_step), JumpThreshold(jump_threshold_factor),
validCallback, options);
}

void RobotState::computeAABB(std::vector<double>& aabb) const
{
assert(checkLinkTransforms());
Expand Down

0 comments on commit cd84de7

Please sign in to comment.