@@ -618,8 +618,9 @@ bool MoveItVisualTools::attachCO(const std::string& name, const std::string& ee_
618
618
return processAttachedCollisionObjectMsg (aco);
619
619
}
620
620
621
- moveit_msgs::CollisionObject MoveItVisualTools::createCollisionBlock (const geometry_msgs::Pose& block_pose,
622
- const std::string& name, double block_size)
621
+ moveit_msgs::CollisionObject MoveItVisualTools::createBlockCollisionObjectMsg (const geometry_msgs::Pose& block_pose,
622
+ const std::string& name,
623
+ double block_size)
623
624
{
624
625
moveit_msgs::CollisionObject collision_obj;
625
626
collision_obj.header .stamp = ros::Time::now ();
@@ -643,12 +644,12 @@ moveit_msgs::CollisionObject MoveItVisualTools::createCollisionBlock(const geome
643
644
bool MoveItVisualTools::publishCollisionBlock (const geometry_msgs::Pose& block_pose, const std::string& name,
644
645
double block_size, const rviz_visual_tools::colors& color)
645
646
{
646
- return processCollisionObjectMsg (createCollisionBlock (block_pose, name, block_size), color);
647
+ return processCollisionObjectMsg (createBlockCollisionObjectMsg (block_pose, name, block_size), color);
647
648
}
648
649
649
- moveit_msgs::CollisionObject MoveItVisualTools::createCollisionObject (const geometry_msgs::Point& point1,
650
- const geometry_msgs::Point& point2,
651
- const std::string& name)
650
+ moveit_msgs::CollisionObject MoveItVisualTools::createCuboidCollisionObjectMsg (const geometry_msgs::Point& point1,
651
+ const geometry_msgs::Point& point2,
652
+ const std::string& name)
652
653
{
653
654
moveit_msgs::CollisionObject collision_obj;
654
655
collision_obj.header .stamp = ros::Time::now ();
@@ -682,11 +683,11 @@ moveit_msgs::CollisionObject MoveItVisualTools::createCollisionObject(const geom
682
683
return collision_obj;
683
684
}
684
685
685
- moveit_msgs::CollisionObject MoveItVisualTools::createCollisionObject (const Eigen::Vector3d& point1,
686
- const Eigen::Vector3d& point2,
687
- const std::string& name)
686
+ moveit_msgs::CollisionObject MoveItVisualTools::createCuboidCollisionObjectMsg (const Eigen::Vector3d& point1,
687
+ const Eigen::Vector3d& point2,
688
+ const std::string& name)
688
689
{
689
- return createCollisionObject (convertPoint (point1), convertPoint (point2), name);
690
+ return createCuboidCollisionObjectMsg (convertPoint (point1), convertPoint (point2), name);
690
691
}
691
692
692
693
bool MoveItVisualTools::publishCollisionCuboid (const Eigen::Vector3d& point1, const Eigen::Vector3d& point2,
@@ -698,23 +699,22 @@ bool MoveItVisualTools::publishCollisionCuboid(const Eigen::Vector3d& point1, co
698
699
bool MoveItVisualTools::publishCollisionCuboid (const geometry_msgs::Point& point1, const geometry_msgs::Point& point2,
699
700
const std::string& name, const rviz_visual_tools::colors& color)
700
701
{
701
- // ROS_INFO_STREAM_NAMED(LOGNAME,"CollisionObject: \n " << collision_obj);
702
- return processCollisionObjectMsg (createCollisionObject (point1, point2, name), color);
702
+ return processCollisionObjectMsg (createCuboidCollisionObjectMsg (point1, point2, name), color);
703
703
}
704
704
705
- moveit_msgs::CollisionObject MoveItVisualTools::createCollisionObject (const geometry_msgs::Pose& pose, double width ,
706
- double depth , double height ,
707
- const std::string& name)
705
+ moveit_msgs::CollisionObject MoveItVisualTools::createCuboidCollisionObjectMsg (const geometry_msgs::Pose& block_pose ,
706
+ double width , double depth ,
707
+ double height, const std::string& name)
708
708
{
709
709
moveit_msgs::CollisionObject collision_obj;
710
710
collision_obj.header .stamp = ros::Time::now ();
711
711
collision_obj.header .frame_id = base_frame_;
712
712
collision_obj.id = name;
713
713
collision_obj.operation = moveit_msgs::CollisionObject::ADD;
714
714
715
- // Calculate center pose
715
+ // Calculate center block_pose
716
716
collision_obj.primitive_poses .resize (1 );
717
- collision_obj.primitive_poses [0 ] = pose ;
717
+ collision_obj.primitive_poses [0 ] = block_pose ;
718
718
719
719
// Calculate scale
720
720
collision_obj.primitives .resize (1 );
@@ -736,29 +736,27 @@ moveit_msgs::CollisionObject MoveItVisualTools::createCollisionObject(const geom
736
736
return collision_obj;
737
737
}
738
738
739
- moveit_msgs::CollisionObject MoveItVisualTools::createCollisionObject (const Eigen::Isometry3d& pose, double width ,
740
- double depth , double height ,
741
- const std::string& name)
739
+ moveit_msgs::CollisionObject MoveItVisualTools::createCuboidCollisionObjectMsg (const Eigen::Isometry3d& block_pose ,
740
+ double width , double depth ,
741
+ double height, const std::string& name)
742
742
{
743
- geometry_msgs::Pose pose_msg = tf2::toMsg (pose );
744
- return createCollisionObject (pose_msg, width, depth, height, name, color );
743
+ geometry_msgs::Pose pose_msg = tf2::toMsg (block_pose );
744
+ return createCuboidCollisionObjectMsg (pose_msg, width, depth, height, name);
745
745
}
746
746
747
- bool MoveItVisualTools::publishCollisionCuboid (const Eigen::Isometry3d& pose, double width, double depth, double height,
748
- const std::string& name, const rviz_visual_tools::colors& color)
747
+ bool MoveItVisualTools::publishCollisionCuboid (const Eigen::Isometry3d& block_pose, double width, double depth,
748
+ double height, const std::string& name,
749
+ const rviz_visual_tools::colors& color)
749
750
{
750
- geometry_msgs::Pose pose_msg = tf2::toMsg (pose );
751
+ geometry_msgs::Pose pose_msg = tf2::toMsg (block_pose );
751
752
return publishCollisionCuboid (pose_msg, width, depth, height, name, color);
752
753
}
753
754
754
- bool MoveItVisualTools::publishCollisionCuboid (const moveit_msgs::CollisionObject& collision_obj,
755
- const rviz_visual_tools::colors& color)
756
-
757
- bool MoveItVisualTools::publishCollisionCuboid(const geometry_msgs::Pose& pose, double width, double depth,
755
+ bool MoveItVisualTools::publishCollisionCuboid (const geometry_msgs::Pose& block_pose, double width, double depth,
758
756
double height, const std::string& name,
759
757
const rviz_visual_tools::colors& color)
760
758
{
761
- return processCollisionObjectMsg (createCollisionObject (pose , width, depth, height, name, color ), color);
759
+ return processCollisionObjectMsg (createCuboidCollisionObjectMsg (block_pose , width, depth, height, name), color);
762
760
}
763
761
764
762
bool MoveItVisualTools::publishCollisionFloor (double z, const std::string& plane_name,
0 commit comments