Skip to content

Commit

Permalink
Use size_t for index variables
Browse files Browse the repository at this point in the history
  • Loading branch information
tylerjw committed Dec 30, 2021
1 parent 908128d commit 765e8ab
Show file tree
Hide file tree
Showing 7 changed files with 19 additions and 19 deletions.
16 changes: 8 additions & 8 deletions moveit_core/robot_model/include/moveit/robot_model/joint_model.h
Original file line number Diff line number Diff line change
Expand Up @@ -83,7 +83,7 @@ class LinkModel;
class JointModel;

/** \brief Data type for holding mappings from variable names to their position in a state vector */
typedef std::map<std::string, int> VariableIndexMap;
typedef std::map<std::string, size_t> VariableIndexMap;

/** \brief Data type for holding mappings from variable names to their bounds */
using VariableBoundsMap = std::map<std::string, VariableBounds>;
Expand Down Expand Up @@ -200,31 +200,31 @@ class JointModel
}

/** \brief Get the index of this joint's first variable within the full robot state */
int getFirstVariableIndex() const
size_t getFirstVariableIndex() const
{
return first_variable_index_;
}

/** \brief Set the index of this joint's first variable within the full robot state */
void setFirstVariableIndex(int index)
void setFirstVariableIndex(size_t index)
{
first_variable_index_ = index;
}

/** \brief Get the index of this joint within the robot model */
int getJointIndex() const
size_t getJointIndex() const
{
return joint_index_;
}

/** \brief Set the index of this joint within the robot model */
void setJointIndex(int index)
void setJointIndex(size_t index)
{
joint_index_ = index;
}

/** \brief Get the index of the variable within this joint */
int getLocalVariableIndex(const std::string& variable) const;
size_t getLocalVariableIndex(const std::string& variable) const;

/** @} */

Expand Down Expand Up @@ -514,10 +514,10 @@ class JointModel
double distance_factor_;

/** \brief The index of this joint's first variable, in the complete robot state */
int first_variable_index_;
size_t first_variable_index_;

/** \brief Index for this joint in the array of joints of the complete model */
int joint_index_;
size_t joint_index_;
};

/** \brief Operator overload for printing variable bounds to a stream */
Expand Down
Original file line number Diff line number Diff line change
Expand Up @@ -83,12 +83,12 @@ class LinkModel
}

/** \brief The index of this joint when traversing the kinematic tree in depth first fashion */
int getLinkIndex() const
size_t getLinkIndex() const
{
return link_index_;
}

void setLinkIndex(int index)
void setLinkIndex(size_t index)
{
link_index_ = index;
}
Expand Down Expand Up @@ -282,7 +282,7 @@ class LinkModel
int first_collision_body_transform_index_;

/** \brief Index of the transform for this link in the full robot frame */
int link_index_;
size_t link_index_;
};
} // namespace core
} // namespace moveit
Original file line number Diff line number Diff line change
Expand Up @@ -444,7 +444,7 @@ class RobotModel
std::vector<std::string>& missing_variables) const;

/** \brief Get the index of a variable in the robot state */
int getVariableIndex(const std::string& variable) const;
size_t getVariableIndex(const std::string& variable) const;

/** \brief Get the deepest joint in the kinematic tree that is a common parent of both joints passed as argument */
const JointModel* getCommonRoot(const JointModel* a, const JointModel* b) const
Expand Down
6 changes: 3 additions & 3 deletions moveit_core/robot_model/src/joint_model.cpp
Original file line number Diff line number Diff line change
Expand Up @@ -54,8 +54,8 @@ JointModel::JointModel(const std::string& name)
, mimic_offset_(0.0)
, passive_(false)
, distance_factor_(1.0)
, first_variable_index_(-1)
, joint_index_(-1)
, first_variable_index_(0)
, joint_index_(0)
{
}

Expand All @@ -82,7 +82,7 @@ std::string JointModel::getTypeName() const
}
}

int JointModel::getLocalVariableIndex(const std::string& variable) const
size_t JointModel::getLocalVariableIndex(const std::string& variable) const
{
VariableIndexMap::const_iterator it = variable_index_map_.find(variable);
if (it == variable_index_map_.end())
Expand Down
2 changes: 1 addition & 1 deletion moveit_core/robot_model/src/link_model.cpp
Original file line number Diff line number Diff line change
Expand Up @@ -51,7 +51,7 @@ LinkModel::LinkModel(const std::string& name)
, is_parent_joint_fixed_(false)
, joint_origin_transform_is_identity_(true)
, first_collision_body_transform_index_(-1)
, link_index_(-1)
, link_index_(0)
{
joint_origin_transform_.setIdentity();
}
Expand Down
2 changes: 1 addition & 1 deletion moveit_core/robot_model/src/robot_model.cpp
Original file line number Diff line number Diff line change
Expand Up @@ -1349,7 +1349,7 @@ void RobotModel::getMissingVariableNames(const std::vector<std::string>& variabl
missing_variables.push_back(variable_name);
}

int RobotModel::getVariableIndex(const std::string& variable) const
size_t RobotModel::getVariableIndex(const std::string& variable) const
{
VariableIndexMap::const_iterator it = joint_variables_index_map_.find(variable);
if (it == joint_variables_index_map_.end())
Expand Down
4 changes: 2 additions & 2 deletions moveit_core/robot_model/test/test.cpp
Original file line number Diff line number Diff line change
Expand Up @@ -71,13 +71,13 @@ TEST_F(LoadPlanningModelsPr2, Model)
const std::vector<const moveit::core::JointModel*>& joints = robot_model_->getJointModels();
for (std::size_t i = 0; i < joints.size(); ++i)
{
ASSERT_EQ(joints[i]->getJointIndex(), static_cast<int>(i));
ASSERT_EQ(joints[i]->getJointIndex(), i);
ASSERT_EQ(robot_model_->getJointModel(joints[i]->getName()), joints[i]);
}
const std::vector<const moveit::core::LinkModel*>& links = robot_model_->getLinkModels();
for (std::size_t i = 0; i < links.size(); ++i)
{
ASSERT_EQ(links[i]->getLinkIndex(), static_cast<int>(i));
ASSERT_EQ(links[i]->getLinkIndex(), i);
}
moveit::tools::Profiler::Status();
}
Expand Down

0 comments on commit 765e8ab

Please sign in to comment.