Skip to content

Commit

Permalink
Convert all moveit_msg messages namespace (#30)
Browse files Browse the repository at this point in the history
  • Loading branch information
davetcoleman committed Mar 6, 2019
1 parent c9c30a2 commit 8dddba4
Show file tree
Hide file tree
Showing 182 changed files with 1,174 additions and 1,171 deletions.
Original file line number Diff line number Diff line change
Expand Up @@ -90,7 +90,7 @@ class AllowedCollisionMatrix
AllowedCollisionMatrix(const std::vector<std::string>& names, bool allowed = false);

/** @brief Construct the structure from a message representation */
AllowedCollisionMatrix(const moveit_msgs::AllowedCollisionMatrix& msg);
AllowedCollisionMatrix(const moveit_msgs::msg::AllowedCollisionMatrix& msg);

/** @brief Copy constructor */
AllowedCollisionMatrix(const AllowedCollisionMatrix& acm);
Expand Down Expand Up @@ -191,7 +191,7 @@ class AllowedCollisionMatrix
void getAllEntryNames(std::vector<std::string>& names) const;

/** @brief Get the allowed collision matrix as a message */
void getMessage(moveit_msgs::AllowedCollisionMatrix& msg) const;
void getMessage(moveit_msgs::msg::AllowedCollisionMatrix& msg) const;

/** @brief Clear the allowed collision matrix */
void clear();
Expand Down
Original file line number Diff line number Diff line change
Expand Up @@ -279,16 +279,16 @@ class CollisionRobot
void setScale(double scale);

/** @brief Set the link padding from a vector of messages*/
void setPadding(const std::vector<moveit_msgs::LinkPadding>& padding);
void setPadding(const std::vector<moveit_msgs::msg::LinkPadding>& padding);

/** @brief Get the link padding as a vector of messages*/
void getPadding(std::vector<moveit_msgs::LinkPadding>& padding) const;
void getPadding(std::vector<moveit_msgs::msg::LinkPadding>& padding) const;

/** @brief Set the link scaling from a vector of messages*/
void setScale(const std::vector<moveit_msgs::LinkScale>& scale);
void setScale(const std::vector<moveit_msgs::msg::LinkScale>& scale);

/** @brief Get the link scaling as a vector of messages*/
void getScale(std::vector<moveit_msgs::LinkScale>& scale) const;
void getScale(std::vector<moveit_msgs::msg::LinkScale>& scale) const;

protected:
/** @brief When the scale or padding is changed for a set of links by any of the functions in this class,
Expand Down
Original file line number Diff line number Diff line change
Expand Up @@ -69,8 +69,8 @@ void removeOverlapping(std::set<CostSource>& cost_sources, double overlap_fracti

bool getSensorPositioning(geometry_msgs::Point& point, const std::set<CostSource>& cost_sources);

void costSourceToMsg(const CostSource& cost_source, moveit_msgs::CostSource& msg);
void contactToMsg(const Contact& contact, moveit_msgs::ContactInformation& msg);
void costSourceToMsg(const CostSource& cost_source, moveit_msgs::msg::CostSource& msg);
void contactToMsg(const Contact& contact, moveit_msgs::msg::ContactInformation& msg);
}

#endif
4 changes: 2 additions & 2 deletions moveit_core/collision_detection/src/collision_matrix.cpp
Original file line number Diff line number Diff line change
Expand Up @@ -51,7 +51,7 @@ AllowedCollisionMatrix::AllowedCollisionMatrix(const std::vector<std::string>& n
setEntry(names[i], names[j], allowed);
}

AllowedCollisionMatrix::AllowedCollisionMatrix(const moveit_msgs::AllowedCollisionMatrix& msg)
AllowedCollisionMatrix::AllowedCollisionMatrix(const moveit_msgs::msg::AllowedCollisionMatrix& msg)
{
if (msg.entry_names.size() != msg.entry_values.size() ||
msg.default_entry_names.size() != msg.default_entry_values.size())
Expand Down Expand Up @@ -332,7 +332,7 @@ void AllowedCollisionMatrix::getAllEntryNames(std::vector<std::string>& names) c
names.push_back(entry.first);
}

void AllowedCollisionMatrix::getMessage(moveit_msgs::AllowedCollisionMatrix& msg) const
void AllowedCollisionMatrix::getMessage(moveit_msgs::msg::AllowedCollisionMatrix& msg) const
{
msg.entry_names.clear();
msg.entry_values.clear();
Expand Down
12 changes: 6 additions & 6 deletions moveit_core/collision_detection/src/collision_robot.cpp
Original file line number Diff line number Diff line change
Expand Up @@ -202,7 +202,7 @@ const std::map<std::string, double>& CollisionRobot::getLinkScale() const
return link_scale_;
}

void CollisionRobot::setPadding(const std::vector<moveit_msgs::LinkPadding>& padding)
void CollisionRobot::setPadding(const std::vector<moveit_msgs::msg::LinkPadding>& padding)
{
std::vector<std::string> u;
for (const auto& p : padding)
Expand All @@ -216,7 +216,7 @@ void CollisionRobot::setPadding(const std::vector<moveit_msgs::LinkPadding>& pad
updatedPaddingOrScaling(u);
}

void CollisionRobot::setScale(const std::vector<moveit_msgs::LinkScale>& scale)
void CollisionRobot::setScale(const std::vector<moveit_msgs::msg::LinkScale>& scale)
{
std::vector<std::string> u;
for (const auto& s : scale)
Expand All @@ -230,24 +230,24 @@ void CollisionRobot::setScale(const std::vector<moveit_msgs::LinkScale>& scale)
updatedPaddingOrScaling(u);
}

void CollisionRobot::getPadding(std::vector<moveit_msgs::LinkPadding>& padding) const
void CollisionRobot::getPadding(std::vector<moveit_msgs::msg::LinkPadding>& padding) const
{
padding.clear();
for (const auto& lp : link_padding_)
{
moveit_msgs::LinkPadding lp_msg;
moveit_msgs::msg::LinkPadding lp_msg;
lp_msg.link_name = lp.first;
lp_msg.padding = lp.second;
padding.push_back(lp_msg);
}
}

void CollisionRobot::getScale(std::vector<moveit_msgs::LinkScale>& scale) const
void CollisionRobot::getScale(std::vector<moveit_msgs::msg::LinkScale>& scale) const
{
scale.clear();
for (const auto& ls : link_scale_)
{
moveit_msgs::LinkScale ls_msg;
moveit_msgs::msg::LinkScale ls_msg;
ls_msg.link_name = ls.first;
ls_msg.scale = ls.second;
scale.push_back(ls_msg);
Expand Down
16 changes: 8 additions & 8 deletions moveit_core/collision_detection/src/collision_tools.cpp
Original file line number Diff line number Diff line change
Expand Up @@ -259,7 +259,7 @@ void removeCostSources(std::set<CostSource>& cost_sources, const std::set<CostSo
}
}

void costSourceToMsg(const CostSource& cost_source, moveit_msgs::CostSource& msg)
void costSourceToMsg(const CostSource& cost_source, moveit_msgs::msg::CostSource& msg)
{
msg.cost_density = cost_source.cost;
msg.aabb_min.x = cost_source.aabb_min[0];
Expand All @@ -270,25 +270,25 @@ void costSourceToMsg(const CostSource& cost_source, moveit_msgs::CostSource& msg
msg.aabb_max.z = cost_source.aabb_max[2];
}

void contactToMsg(const Contact& contact, moveit_msgs::ContactInformation& msg)
void contactToMsg(const Contact& contact, moveit_msgs::msg::ContactInformation& msg)
{
msg.position = tf2::toMsg(contact.pos);
tf2::toMsg(contact.normal, msg.normal);
msg.depth = contact.depth;
msg.contact_body_1 = contact.body_name_1;
msg.contact_body_2 = contact.body_name_2;
if (contact.body_type_1 == BodyTypes::ROBOT_LINK)
msg.body_type_1 = moveit_msgs::ContactInformation::ROBOT_LINK;
msg.body_type_1 = moveit_msgs::msg::ContactInformation::ROBOT_LINK;
else if (contact.body_type_1 == BodyTypes::ROBOT_ATTACHED)
msg.body_type_1 = moveit_msgs::ContactInformation::ROBOT_ATTACHED;
msg.body_type_1 = moveit_msgs::msg::ContactInformation::ROBOT_ATTACHED;
else
msg.body_type_1 = moveit_msgs::ContactInformation::WORLD_OBJECT;
msg.body_type_1 = moveit_msgs::msg::ContactInformation::WORLD_OBJECT;
if (contact.body_type_2 == BodyTypes::ROBOT_LINK)
msg.body_type_2 = moveit_msgs::ContactInformation::ROBOT_LINK;
msg.body_type_2 = moveit_msgs::msg::ContactInformation::ROBOT_LINK;
else if (contact.body_type_2 == BodyTypes::ROBOT_ATTACHED)
msg.body_type_2 = moveit_msgs::ContactInformation::ROBOT_ATTACHED;
msg.body_type_2 = moveit_msgs::msg::ContactInformation::ROBOT_ATTACHED;
else
msg.body_type_2 = moveit_msgs::ContactInformation::WORLD_OBJECT;
msg.body_type_2 = moveit_msgs::msg::ContactInformation::WORLD_OBJECT;
}

} // end of namespace collision_detection
Original file line number Diff line number Diff line change
Expand Up @@ -87,7 +87,7 @@ class ConstraintSampler
* @return True if the configuration is successful. If true, \ref isValid should also true.
* If false, \ref isValid should return false
*/
virtual bool configure(const moveit_msgs::Constraints& constr) = 0;
virtual bool configure(const moveit_msgs::msg::Constraints& constr) = 0;

/**
* \brief Gets the group name set in the constructor
Expand Down
Original file line number Diff line number Diff line change
Expand Up @@ -56,10 +56,10 @@ class ConstraintSamplerAllocator
}

virtual ConstraintSamplerPtr alloc(const planning_scene::PlanningSceneConstPtr& scene, const std::string& group_name,
const moveit_msgs::Constraints& constr) = 0;
const moveit_msgs::msg::Constraints& constr) = 0;

virtual bool canService(const planning_scene::PlanningSceneConstPtr& scene, const std::string& group_name,
const moveit_msgs::Constraints& constr) const = 0;
const moveit_msgs::msg::Constraints& constr) const = 0;
};
}

Expand Down
Original file line number Diff line number Diff line change
Expand Up @@ -46,7 +46,7 @@ MOVEIT_CLASS_FORWARD(ConstraintSamplerManager);

/**
* \brief This class assists in the generation of a ConstraintSampler for a
* particular group from a moveit_msgs::Constraints.
* particular group from a moveit_msgs::msg::Constraints.
*
* It contains logic that will generate either a
* JointConstraintSampler, an IKConstraintSampler, or a
Expand Down Expand Up @@ -90,7 +90,7 @@ class ConstraintSamplerManager
* or an empty pointer if none could be allocated
*/
ConstraintSamplerPtr selectSampler(const planning_scene::PlanningSceneConstPtr& scene, const std::string& group_name,
const moveit_msgs::Constraints& constr) const;
const moveit_msgs::msg::Constraints& constr) const;

/**
* \brief Default logic to select a ConstraintSampler given a
Expand Down Expand Up @@ -137,7 +137,7 @@ class ConstraintSamplerManager
*/
static ConstraintSamplerPtr selectDefaultSampler(const planning_scene::PlanningSceneConstPtr& scene,
const std::string& group_name,
const moveit_msgs::Constraints& constr);
const moveit_msgs::msg::Constraints& constr);

private:
std::vector<ConstraintSamplerAllocatorPtr>
Expand Down
Original file line number Diff line number Diff line change
Expand Up @@ -46,13 +46,13 @@ void visualizeDistribution(const ConstraintSamplerPtr& sampler, const robot_stat
const std::string& link_name, unsigned int sample_count,
visualization_msgs::MarkerArray& markers);

void visualizeDistribution(const moveit_msgs::Constraints& constr, const planning_scene::PlanningSceneConstPtr& scene,
void visualizeDistribution(const moveit_msgs::msg::Constraints& constr, const planning_scene::PlanningSceneConstPtr& scene,
const std::string& group, const std::string& link_name, unsigned int sample_count,
visualization_msgs::MarkerArray& markers);

double countSamplesPerSecond(const ConstraintSamplerPtr& sampler, const robot_state::RobotState& reference_state);

double countSamplesPerSecond(const moveit_msgs::Constraints& constr, const planning_scene::PlanningSceneConstPtr& scene,
double countSamplesPerSecond(const moveit_msgs::msg::Constraints& constr, const planning_scene::PlanningSceneConstPtr& scene,
const std::string& group);
}

Expand Down
Original file line number Diff line number Diff line change
Expand Up @@ -88,7 +88,7 @@ class JointConstraintSampler : public ConstraintSampler
*
* @return True if the conditions are met, otherwise false
*/
bool configure(const moveit_msgs::Constraints& constr) override;
bool configure(const moveit_msgs::msg::Constraints& constr) override;

/**
* \brief Configures a joint constraint given a vector of constraints.
Expand Down Expand Up @@ -332,7 +332,7 @@ class IKConstraintSampler : public ConstraintSampler
* exist and the overloaded configuration function returns true.
* Otherwise, returns false.
*/
bool configure(const moveit_msgs::Constraints& constr) override;
bool configure(const moveit_msgs::msg::Constraints& constr) override;

/**
* \brief Configures the Constraint given a IKSamplingPose.
Expand Down
Original file line number Diff line number Diff line change
Expand Up @@ -117,7 +117,7 @@ class UnionConstraintSampler : public ConstraintSampler
*
* @return Always true
*/
bool configure(const moveit_msgs::Constraints& constr) override
bool configure(const moveit_msgs::msg::Constraints& constr) override
{
return true;
}
Expand All @@ -129,7 +129,7 @@ class UnionConstraintSampler : public ConstraintSampler
*
* @return Always true
*/
virtual bool canService(const moveit_msgs::Constraints& constr) const
virtual bool canService(const moveit_msgs::msg::Constraints& constr) const
{
return true;
}
Expand Down
Original file line number Diff line number Diff line change
Expand Up @@ -42,7 +42,7 @@
constraint_samplers::ConstraintSamplerPtr
constraint_samplers::ConstraintSamplerManager::selectSampler(const planning_scene::PlanningSceneConstPtr& scene,
const std::string& group_name,
const moveit_msgs::Constraints& constr) const
const moveit_msgs::msg::Constraints& constr) const
{
for (std::size_t i = 0; i < sampler_alloc_.size(); ++i)
if (sampler_alloc_[i]->canService(scene, group_name, constr))
Expand All @@ -55,7 +55,7 @@ constraint_samplers::ConstraintSamplerManager::selectSampler(const planning_scen
constraint_samplers::ConstraintSamplerPtr
constraint_samplers::ConstraintSamplerManager::selectDefaultSampler(const planning_scene::PlanningSceneConstPtr& scene,
const std::string& group_name,
const moveit_msgs::Constraints& constr)
const moveit_msgs::msg::Constraints& constr)
{
const robot_model::JointModelGroup* jmg = scene->getRobotModel()->getJointModelGroup(group_name);
if (!jmg)
Expand Down Expand Up @@ -301,7 +301,7 @@ constraint_samplers::ConstraintSamplerManager::selectDefaultSampler(const planni
it != ik_subgroup_alloc.end(); ++it)
{
// construct a sub-set of constraints that operate on the sub-group for which we have an IK allocator
moveit_msgs::Constraints sub_constr;
moveit_msgs::msg::Constraints sub_constr;
for (std::size_t p = 0; p < constr.position_constraints.size(); ++p)
if (it->first->hasLinkModel(constr.position_constraints[p].link_name))
if (used_p.find(p) == used_p.end())
Expand Down
Original file line number Diff line number Diff line change
Expand Up @@ -37,7 +37,7 @@
#include <moveit/constraint_samplers/constraint_sampler_tools.h>
#include <moveit/constraint_samplers/constraint_sampler_manager.h>

void constraint_samplers::visualizeDistribution(const moveit_msgs::Constraints& constr,
void constraint_samplers::visualizeDistribution(const moveit_msgs::msg::Constraints& constr,
const planning_scene::PlanningSceneConstPtr& scene,
const std::string& group, const std::string& link_name,
unsigned int sample_count, visualization_msgs::MarkerArray& markers)
Expand All @@ -46,7 +46,7 @@ void constraint_samplers::visualizeDistribution(const moveit_msgs::Constraints&
link_name, sample_count, markers);
}

double constraint_samplers::countSamplesPerSecond(const moveit_msgs::Constraints& constr,
double constraint_samplers::countSamplesPerSecond(const moveit_msgs::msg::Constraints& constr,
const planning_scene::PlanningSceneConstPtr& scene,
const std::string& group)
{
Expand Down
Original file line number Diff line number Diff line change
Expand Up @@ -41,7 +41,7 @@

namespace constraint_samplers
{
bool JointConstraintSampler::configure(const moveit_msgs::Constraints& constr)
bool JointConstraintSampler::configure(const moveit_msgs::msg::Constraints& constr)
{
// construct the constraints
std::vector<kinematic_constraints::JointConstraint> jc;
Expand Down Expand Up @@ -276,7 +276,7 @@ bool IKConstraintSampler::configure(const IKSamplingPose& sp)
return is_valid_;
}

bool IKConstraintSampler::configure(const moveit_msgs::Constraints& constr)
bool IKConstraintSampler::configure(const moveit_msgs::msg::Constraints& constr)
{
for (std::size_t p = 0; p < constr.position_constraints.size(); ++p)
for (std::size_t o = 0; o < constr.orientation_constraints.size(); ++o)
Expand Down Expand Up @@ -509,16 +509,16 @@ namespace
void samplingIkCallbackFnAdapter(robot_state::RobotState* state, const robot_model::JointModelGroup* jmg,
const robot_state::GroupStateValidityCallbackFn& constraint,
const geometry_msgs::Pose& /*unused*/, const std::vector<double>& ik_sol,
moveit_msgs::MoveItErrorCodes& error_code)
moveit_msgs::msg::MoveItErrorCodes& error_code)
{
const std::vector<unsigned int>& bij = jmg->getKinematicsSolverJointBijection();
std::vector<double> solution(bij.size());
for (std::size_t i = 0; i < bij.size(); ++i)
solution[i] = ik_sol[bij[i]];
if (constraint(state, jmg, &solution[0]))
error_code.val = moveit_msgs::MoveItErrorCodes::SUCCESS;
error_code.val = moveit_msgs::msg::MoveItErrorCodes::SUCCESS;
else
error_code.val = moveit_msgs::MoveItErrorCodes::NO_IK_SOLUTION;
error_code.val = moveit_msgs::msg::MoveItErrorCodes::NO_IK_SOLUTION;
}
}

Expand Down Expand Up @@ -622,7 +622,7 @@ bool IKConstraintSampler::callIK(const geometry_msgs::Pose& ik_query,
seed[i] = vals[ik_joint_bijection[i]];

std::vector<double> ik_sol;
moveit_msgs::MoveItErrorCodes error;
moveit_msgs::msg::MoveItErrorCodes error;

if (adapted_ik_validity_callback ?
kb_->searchPositionIK(ik_query, seed, timeout, ik_sol, adapted_ik_validity_callback, error) :
Expand All @@ -638,9 +638,9 @@ bool IKConstraintSampler::callIK(const geometry_msgs::Pose& ik_query,
}
else
{
if (error.val != moveit_msgs::MoveItErrorCodes::NO_IK_SOLUTION &&
error.val != moveit_msgs::MoveItErrorCodes::INVALID_ROBOT_STATE &&
error.val != moveit_msgs::MoveItErrorCodes::TIMED_OUT)
if (error.val != moveit_msgs::msg::MoveItErrorCodes::NO_IK_SOLUTION &&
error.val != moveit_msgs::msg::MoveItErrorCodes::INVALID_ROBOT_STATE &&
error.val != moveit_msgs::msg::MoveItErrorCodes::TIMED_OUT)
ROS_ERROR_NAMED("constraint_samplers", "IK solver failed with error %d", error.val);
else if (verbose_)
ROS_INFO_NAMED("constraint_samplers", "IK failed");
Expand Down
6 changes: 3 additions & 3 deletions moveit_core/constraint_samplers/test/pr2_arm_ik.cpp
Original file line number Diff line number Diff line change
Expand Up @@ -151,9 +151,9 @@ bool PR2ArmIK::init(const urdf::ModelInterface& robot_model, const std::string&
return true;
}

void PR2ArmIK::addJointToChainInfo(const urdf::JointConstSharedPtr& joint, moveit_msgs::KinematicSolverInfo& info)
void PR2ArmIK::addJointToChainInfo(const urdf::JointConstSharedPtr& joint, moveit_msgs::msg::KinematicSolverInfo& info)
{
moveit_msgs::JointLimits limit;
moveit_msgs::msg::JointLimits limit;
info.joint_names.push_back(joint->name); // Joints are coming in reverse order

if (joint->type != urdf::Joint::CONTINUOUS)
Expand Down Expand Up @@ -189,7 +189,7 @@ void PR2ArmIK::addJointToChainInfo(const urdf::JointConstSharedPtr& joint, movei
info.limits.push_back(limit);
}

void PR2ArmIK::getSolverInfo(moveit_msgs::KinematicSolverInfo& info)
void PR2ArmIK::getSolverInfo(moveit_msgs::msg::KinematicSolverInfo& info)
{
info = solver_info_;
}
Expand Down
Loading

0 comments on commit 8dddba4

Please sign in to comment.