Skip to content

Commit

Permalink
changing variable names for consistency and clang (#33)
Browse files Browse the repository at this point in the history
  • Loading branch information
mlautman authored and v4hn committed Aug 28, 2018
1 parent 884dae7 commit d5cdd6a
Show file tree
Hide file tree
Showing 2 changed files with 9 additions and 8 deletions.
8 changes: 4 additions & 4 deletions include/moveit_visual_tools/moveit_visual_tools.h
Original file line number Diff line number Diff line change
Expand Up @@ -357,11 +357,11 @@ class MoveItVisualTools : public rviz_visual_tools::RvizVisualTools
* \param color to display the collision object with
* \return true on sucess
**/
bool publishCollisionCuboid(const Eigen::Affine3d& pose, double width, double depth, double height, const std::string& name,
const rviz_visual_tools::colors& color);
bool publishCollisionCuboid(const Eigen::Affine3d& pose, double width, double depth, double height,
const std::string& name, const rviz_visual_tools::colors& color);

bool publishCollisionCuboid(const geometry_msgs::Pose& pose, double x, double y, double z, const std::string& name,
const rviz_visual_tools::colors& color);
bool publishCollisionCuboid(const geometry_msgs::Pose& pose, double width, double depth, double height,
const std::string& name, const rviz_visual_tools::colors& color);

/**
* \brief Create a MoveIt Collision cylinder between two points
Expand Down
9 changes: 5 additions & 4 deletions src/moveit_visual_tools.cpp
Original file line number Diff line number Diff line change
Expand Up @@ -687,16 +687,17 @@ bool MoveItVisualTools::publishCollisionCuboid(const geometry_msgs::Point& point
return processCollisionObjectMsg(collision_obj, color);
}

bool MoveItVisualTools::publishCollisionCuboid(const Eigen::Affine3d& pose, double x, double y, double z,
bool MoveItVisualTools::publishCollisionCuboid(const Eigen::Affine3d& pose, double width, double depth, double height,
const std::string& name, const rviz_visual_tools::colors& color)
{
geometry_msgs::Pose pose_msg;
tf::poseEigenToMsg(pose, pose_msg);
return publishCollisionCuboid(pose_msg, x, y, z, name, color);
return publishCollisionCuboid(pose_msg, width, depth, height, name, color);
}

bool MoveItVisualTools::publishCollisionCuboid(const geometry_msgs::Pose& pose, double width, double depth, double height,
const std::string& name, const rviz_visual_tools::colors& color)
bool MoveItVisualTools::publishCollisionCuboid(const geometry_msgs::Pose& pose, double width, double depth,
double height, const std::string& name,
const rviz_visual_tools::colors& color)
{
moveit_msgs::CollisionObject collision_obj;
collision_obj.header.stamp = ros::Time::now();
Expand Down

0 comments on commit d5cdd6a

Please sign in to comment.