Skip to content

Commit

Permalink
Optimize format.
Browse files Browse the repository at this point in the history
  • Loading branch information
cc0h committed Mar 26, 2024
1 parent 7843d78 commit ff24773
Show file tree
Hide file tree
Showing 3 changed files with 6 additions and 4 deletions.
Original file line number Diff line number Diff line change
Expand Up @@ -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.;
}
Expand Down
5 changes: 3 additions & 2 deletions engineer_middleware/include/engineer_middleware/step.h
Original file line number Diff line number Diff line change
Expand Up @@ -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"));
Expand Down Expand Up @@ -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_{};
Expand Down
3 changes: 2 additions & 1 deletion engineer_middleware/src/middleware.cpp
Original file line number Diff line number Diff line change
Expand Up @@ -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
Expand Down

0 comments on commit ff24773

Please sign in to comment.