From ff247735771b9b88ea9236f136b4b4d2a4db41a7 Mon Sep 17 00:00:00 2001 From: cc0h <7921166012@qq.com> Date: Tue, 26 Mar 2024 19:54:50 +0800 Subject: [PATCH] Optimize format. --- .../include/engineer_middleware/auto_exchange.h | 2 +- engineer_middleware/include/engineer_middleware/step.h | 5 +++-- engineer_middleware/src/middleware.cpp | 3 ++- 3 files changed, 6 insertions(+), 4 deletions(-) diff --git a/engineer_middleware/include/engineer_middleware/auto_exchange.h b/engineer_middleware/include/engineer_middleware/auto_exchange.h index ee1b25b..687e4f6 100644 --- a/engineer_middleware/include/engineer_middleware/auto_exchange.h +++ b/engineer_middleware/include/engineer_middleware/auto_exchange.h @@ -783,7 +783,7 @@ class UnionMove : public ProgressBase } void initComputerValue() { - for (double & servo_scale : servo_scales_) + for (double& servo_scale : servo_scales_) { servo_scale = 0.; } diff --git a/engineer_middleware/include/engineer_middleware/step.h b/engineer_middleware/include/engineer_middleware/step.h index 24fdc4e..60fae69 100644 --- a/engineer_middleware/include/engineer_middleware/step.h +++ b/engineer_middleware/include/engineer_middleware/step.h @@ -50,7 +50,8 @@ class Step moveit::planning_interface::MoveGroupInterface& arm_group, ChassisInterface& chassis_interface, ros::Publisher& hand_pub, ros::Publisher& end_effector_pub, ros::Publisher& gimbal_pub, ros::Publisher& gpio_pub, ros::Publisher& reversal_pub, ros::Publisher& stone_num_pub, ros::Publisher& planning_result_pub, - ros::Publisher& point_cloud_pub, ros::Publisher& ore_rotate_pub, ros::Publisher& ore_lift_pub, ros::Publisher& gimbal_lift_pub) + ros::Publisher& point_cloud_pub, ros::Publisher& ore_rotate_pub, ros::Publisher& ore_lift_pub, + ros::Publisher& gimbal_lift_pub) : planning_result_pub_(planning_result_pub), point_cloud_pub_(point_cloud_pub), arm_group_(arm_group) { ROS_ASSERT(step.hasMember("step")); @@ -194,7 +195,7 @@ class Step MoveitMotionBase* arm_motion_{}; HandMotion* hand_motion_{}; JointPositionMotion* end_effector_motion_{}; - JointPointMotion* ore_rotate_motion_{},* ore_lift_motion_{},* gimbal_lift_motion_{}; + JointPointMotion *ore_rotate_motion_{}, *ore_lift_motion_{}, *gimbal_lift_motion_{}; StoneNumMotion* stone_num_motion_{}; ChassisMotion* chassis_motion_{}; GimbalMotion* gimbal_motion_{}; diff --git a/engineer_middleware/src/middleware.cpp b/engineer_middleware/src/middleware.cpp index f57dee3..701ade3 100644 --- a/engineer_middleware/src/middleware.cpp +++ b/engineer_middleware/src/middleware.cpp @@ -72,7 +72,8 @@ Middleware::Middleware(ros::NodeHandle& nh) step_queues_.insert( std::make_pair(it->first, StepQueue(it->second, scenes_list, tf_, arm_group_, chassis_interface_, hand_pub_, end_effector_pub_, gimbal_pub_, gpio_pub_, reversal_pub_, stone_num_pub_, - planning_result_pub_, point_cloud_pub_, ore_rotate_pub_, ore_lift_pub_, gimbal_lift_pub))); + planning_result_pub_, point_cloud_pub_, ore_rotate_pub_, ore_lift_pub_, + gimbal_lift_pub))); } } else