@@ -428,7 +428,7 @@ class MoveItVisualTools : public rviz_visual_tools::RvizVisualTools
428
428
* \brief Helper for publishCollisionWall
429
429
*/
430
430
void getCollisionWallMsg (double x, double y, double z, double angle, double width, double height,
431
- const std::string name, moveit_msgs::CollisionObject& collision_obj);
431
+ const std::string& name, moveit_msgs::CollisionObject& collision_obj);
432
432
433
433
/* *
434
434
* \brief Publish a typical room wall
@@ -442,10 +442,10 @@ class MoveItVisualTools : public rviz_visual_tools::RvizVisualTools
442
442
* \return true on sucess
443
443
*/
444
444
bool publishCollisionWall (double x, double y, double angle = 0.0 , double width = 2.0 , double height = 1.5 ,
445
- const std::string name = " wall" ,
445
+ const std::string& name = " wall" ,
446
446
const rviz_visual_tools::colors& color = rviz_visual_tools::GREEN);
447
447
bool publishCollisionWall (double x, double y, double z, double angle = 0.0 , double width = 2.0 , double height = 1.5 ,
448
- const std::string name = " wall" ,
448
+ const std::string& name = " wall" ,
449
449
const rviz_visual_tools::colors& color = rviz_visual_tools::GREEN);
450
450
451
451
/* *
@@ -468,7 +468,8 @@ class MoveItVisualTools : public rviz_visual_tools::RvizVisualTools
468
468
}
469
469
470
470
bool publishCollisionTable (double x, double y, double z, double angle, double width, double height, double depth,
471
- const std::string name, const rviz_visual_tools::colors& color = rviz_visual_tools::GREEN);
471
+ const std::string& name,
472
+ const rviz_visual_tools::colors& color = rviz_visual_tools::GREEN);
472
473
473
474
/* *
474
475
* \brief Load a planning scene to a planning_scene_monitor from file
@@ -550,7 +551,7 @@ class MoveItVisualTools : public rviz_visual_tools::RvizVisualTools
550
551
bool publishTrajectoryPath (const robot_trajectory::RobotTrajectoryPtr& trajectory, bool blocking = false );
551
552
bool publishTrajectoryPath (const robot_trajectory::RobotTrajectory& trajectory, bool blocking = false );
552
553
bool publishTrajectoryPath (const moveit_msgs::RobotTrajectory& trajectory_msg,
553
- const moveit::core::RobotStateConstPtr robot_state, bool blocking = false );
554
+ const moveit::core::RobotStateConstPtr& robot_state, bool blocking = false );
554
555
bool publishTrajectoryPath (const moveit_msgs::RobotTrajectory& trajectory_msg,
555
556
const moveit::core::RobotState& robot_state, bool blocking = false );
556
557
bool publishTrajectoryPath (const moveit_msgs::RobotTrajectory& trajectory_msg,
@@ -568,7 +569,7 @@ class MoveItVisualTools : public rviz_visual_tools::RvizVisualTools
568
569
bool publishTrajectoryLine (const moveit_msgs::RobotTrajectory& trajectory_msg,
569
570
const moveit::core::LinkModel* ee_parent_link, const robot_model::JointModelGroup* arm_jmg,
570
571
const rviz_visual_tools::colors& color = rviz_visual_tools::LIME_GREEN);
571
- bool publishTrajectoryLine (const robot_trajectory::RobotTrajectoryPtr robot_trajectory,
572
+ bool publishTrajectoryLine (const robot_trajectory::RobotTrajectoryPtr& robot_trajectory,
572
573
const moveit::core::LinkModel* ee_parent_link,
573
574
const rviz_visual_tools::colors& color = rviz_visual_tools::LIME_GREEN);
574
575
bool publishTrajectoryLine (const robot_trajectory::RobotTrajectory& robot_trajectory,
@@ -586,7 +587,7 @@ class MoveItVisualTools : public rviz_visual_tools::RvizVisualTools
586
587
bool publishTrajectoryLine (const moveit_msgs::RobotTrajectory& trajectory_msg,
587
588
const robot_model::JointModelGroup* arm_jmg,
588
589
const rviz_visual_tools::colors& color = rviz_visual_tools::LIME_GREEN);
589
- bool publishTrajectoryLine (const robot_trajectory::RobotTrajectoryPtr robot_trajectory,
590
+ bool publishTrajectoryLine (const robot_trajectory::RobotTrajectoryPtr& robot_trajectory,
590
591
const robot_model::JointModelGroup* arm_jmg,
591
592
const rviz_visual_tools::colors& color = rviz_visual_tools::LIME_GREEN);
592
593
bool publishTrajectoryLine (const robot_trajectory::RobotTrajectory& robot_trajectory,
@@ -627,16 +628,16 @@ class MoveItVisualTools : public rviz_visual_tools::RvizVisualTools
627
628
* \param color - how to highlight the robot (solid-ly) if desired, default keeps color as specified in URDF
628
629
* \return true on success
629
630
*/
630
- bool publishRobotState (const std::vector<double > joint_positions, const robot_model::JointModelGroup* jmg,
631
+ bool publishRobotState (const std::vector<double >& joint_positions, const robot_model::JointModelGroup* jmg,
631
632
const rviz_visual_tools::colors& color = rviz_visual_tools::DEFAULT);
632
633
633
634
/* *
634
635
* \brief Publish a complete robot state to Rviz
635
636
* To use, add a RobotState marker to Rviz and subscribe to the DISPLAY_ROBOT_STATE_TOPIC, above
636
637
* \param robot_state - joint values of robot
637
638
* \param color - how to highlight the robot (solid-ly) if desired, default keeps color as specified in URDF
638
- * \param highlight_links - if the |color| is not |DEFAULT|, allows selective robot links to be highlighted. by
639
- * default (empty) all links are highlighted
639
+ * \param highlight_links - if the |color| is not |DEFAULT|, allows selective robot links to be highlighted.
640
+ * By default (empty) all links are highlighted.
640
641
*/
641
642
bool publishRobotState (const moveit::core::RobotState& robot_state,
642
643
const rviz_visual_tools::colors& color = rviz_visual_tools::DEFAULT,
@@ -659,7 +660,7 @@ class MoveItVisualTools : public rviz_visual_tools::RvizVisualTools
659
660
* \brief Print to console the current robot state's joint values within its limits visually
660
661
* \param robot_state - the robot to show
661
662
*/
662
- void showJointLimits (moveit::core::RobotStatePtr robot_state);
663
+ void showJointLimits (const moveit::core::RobotStatePtr& robot_state);
663
664
664
665
/* *
665
666
* @brief Get the planning scene monitor that this class is using
0 commit comments