@@ -328,7 +328,7 @@ class GimbalCommandSender : public TimeStampCommandSenderBase<rm_msgs::GimbalCmd
328328 msg_.traj_yaw = traj_yaw;
329329 msg_.traj_pitch = traj_pitch;
330330 }
331- void setGimbalTrajFrameId (std::string traj_frame_id)
331+ void setGimbalTrajFrameId (const std::string& traj_frame_id)
332332 {
333333 msg_.traj_frame_id = traj_frame_id;
334334 }
@@ -383,6 +383,7 @@ class ShooterCommandSender : public TimeStampCommandSenderBase<rm_msgs::ShootCmd
383383 nh.getParam (" wheel_speed_30" , wheel_speed_30_);
384384 nh.param (" speed_oscillation" , speed_oscillation_, 1.0 );
385385 nh.param (" extra_wheel_speed_once" , extra_wheel_speed_once_, 0 .);
386+ nh.param (" extra_speed_for_deploy" , extra_speed_for_deploy_, 85.0 );
386387 if (!nh.getParam (" auto_wheel_speed" , auto_wheel_speed_))
387388 ROS_INFO (" auto_wheel_speed no defined (namespace: %s), set to false." , nh.getNamespace ().c_str ());
388389 if (!nh.getParam (" target_acceleration_tolerance" , target_acceleration_tolerance_))
@@ -545,6 +546,14 @@ class ShooterCommandSender : public TimeStampCommandSenderBase<rm_msgs::ShootCmd
545546 {
546547 total_extra_wheel_speed_ += extra_wheel_speed_once_;
547548 }
549+ void deploySpeed ()
550+ {
551+ total_extra_wheel_speed_ -= extra_speed_for_deploy_;
552+ }
553+ void exitDeploySpeed ()
554+ {
555+ total_extra_wheel_speed_ += extra_speed_for_deploy_;
556+ }
548557 void setArmorType (uint8_t armor_type)
549558 {
550559 armor_type_ = armor_type;
@@ -571,6 +580,7 @@ class ShooterCommandSender : public TimeStampCommandSenderBase<rm_msgs::ShootCmd
571580 double target_acceleration_tolerance_{};
572581 double extra_wheel_speed_once_{};
573582 double total_extra_wheel_speed_{};
583+ double extra_speed_for_deploy_{};
574584 bool auto_wheel_speed_ = false ;
575585 rm_msgs::TrackData track_data_;
576586 rm_msgs::GimbalDesError gimbal_des_error_;
0 commit comments