standard.h
Go to the documentation of this file.
1 /*******************************************************************************
2  * BSD 3-Clause License
3  *
4  * Copyright (c) 2021, Qiayuan Liao
5  * All rights reserved.
6  *
7  * Redistribution and use in source and binary forms, with or without
8  * modification, are permitted provided that the following conditions are met:
9  *
10  * * Redistributions of source code must retain the above copyright notice, this
11  * list of conditions and the following disclaimer.
12  *
13  * * Redistributions in binary form must reproduce the above copyright notice,
14  * this list of conditions and the following disclaimer in the documentation
15  * and/or other materials provided with the distribution.
16  *
17  * * Neither the name of the copyright holder nor the names of its
18  * contributors may be used to endorse or promote products derived from
19  * this software without specific prior written permission.
20  *
21  * THIS SOFTWARE IS PROVIDED BY THE COPYRIGHT HOLDERS AND CONTRIBUTORS "AS IS"
22  * AND ANY EXPRESS OR IMPLIED WARRANTIES, INCLUDING, BUT NOT LIMITED TO, THE
23  * IMPLIED WARRANTIES OF MERCHANTABILITY AND FITNESS FOR A PARTICULAR PURPOSE
24  * ARE
25  * DISCLAIMED. IN NO EVENT SHALL THE COPYRIGHT HOLDER OR CONTRIBUTORS BE LIABLE
26  * FOR ANY DIRECT, INDIRECT, INCIDENTAL, SPECIAL, EXEMPLARY, OR CONSEQUENTIAL
27  * DAMAGES (INCLUDING, BUT NOT LIMITED TO, PROCUREMENT OF SUBSTITUTE GOODS OR
28  * SERVICES; LOSS OF USE, DATA, OR PROFITS; OR BUSINESS INTERRUPTION) HOWEVER
29  * CAUSED AND ON ANY THEORY OF LIABILITY, WHETHER IN CONTRACT, STRICT LIABILITY,
30  * OR TORT (INCLUDING NEGLIGENCE OR OTHERWISE) ARISING IN ANY WAY OUT OF THE USE
31  * OF THIS SOFTWARE, EVEN IF ADVISED OF THE POSSIBILITY OF SUCH DAMAGE.
32  *******************************************************************************/
33 
34 //
35 // Created by huakang on 2021/1/18.
36 //
37 
38 #pragma once
39 
47 #include <dynamic_reconfigure/server.h>
48 #include <rm_shooter_controllers/ShooterConfig.h>
49 #include <rm_msgs/ShootCmd.h>
50 #include <rm_msgs/ShootState.h>
51 #include <rm_msgs/LocalHeatState.h>
52 
53 #include <utility>
54 
56 {
57 struct Config
58 {
62 };
63 
64 class Controller : public controller_interface::MultiInterfaceController<hardware_interface::EffortJointInterface,
65  rm_control::RobotStateInterface>
66 {
67 public:
68  Controller() = default;
69  bool init(hardware_interface::RobotHW* robot_hw, ros::NodeHandle& root_nh, ros::NodeHandle& controller_nh) override;
70  void update(const ros::Time& time, const ros::Duration& period) override;
71  void starting(const ros::Time& /*time*/) override;
72 
73 private:
74  void stop(const ros::Time& time, const ros::Duration& period);
75  void ready(const ros::Duration& period);
76  void push(const ros::Time& time, const ros::Duration& period);
77  void block(const ros::Time& time, const ros::Duration& period);
78  void setSpeed(const rm_msgs::ShootCmd& cmd);
79  void normalize();
80  void judgeBulletShoot(const ros::Time& time, const ros::Duration& period);
81  void commandCB(const rm_msgs::ShootCmdConstPtr& msg)
82  {
84  }
85 
86  void reconfigCB(rm_shooter_controllers::ShooterConfig& config, uint32_t /*level*/);
87 
89  std::vector<std::vector<effort_controllers::JointVelocityController*>> ctrls_friction_;
91  std::vector<std::vector<double>> wheel_speed_offsets_;
92  std::vector<std::vector<double>> wheel_speed_directions_;
93  int push_per_rotation_{}, count_{};
95  double freq_threshold_{};
96  bool dynamic_reconfig_initialized_ = false;
97  bool state_changed_ = false;
98  bool enter_ready_ = false;
99  bool maybe_block_ = false;
100  int friction_block_count = 0;
101  bool last_friction_wheel_block = false, friction_wheel_block = false;
104  bool has_shoot_ = false, has_shoot_last_ = false;
105  bool wheel_speed_raise_ = true, wheel_speed_drop_ = true;
106  double last_wheel_speed_{};
107 
109  enum
110  {
111  STOP,
113  PUSH,
114  BLOCK
115  };
116  int state_ = STOP;
117  Config config_{};
120  rm_msgs::ShootCmd cmd_;
121  std::shared_ptr<realtime_tools::RealtimePublisher<rm_msgs::LocalHeatState>> local_heat_state_pub_;
122  std::shared_ptr<realtime_tools::RealtimePublisher<rm_msgs::ShootState>> shoot_state_pub_;
124  dynamic_reconfigure::Server<rm_shooter_controllers::ShooterConfig>* d_srv_{};
125 };
126 
127 } // namespace rm_shooter_controllers
realtime_tools::RealtimeBuffer
rm_shooter_controllers::Controller::push_wheel_speed_threshold_
double push_wheel_speed_threshold_
Definition: standard.h:125
rm_shooter_controllers::Controller::friction_block_count
int friction_block_count
Definition: standard.h:131
realtime_tools::RealtimeBuffer::writeFromNonRT
void writeFromNonRT(const T &data)
realtime_publisher.h
rm_shooter_controllers::Controller::cmd_subscriber_
ros::Subscriber cmd_subscriber_
Definition: standard.h:154
rm_shooter_controllers::Controller::has_shoot_last_
bool has_shoot_last_
Definition: standard.h:135
rm_shooter_controllers::Controller::dynamic_reconfig_initialized_
bool dynamic_reconfig_initialized_
Definition: standard.h:127
rm_shooter_controllers::Config::block_overtime
double block_overtime
Definition: standard.h:121
rm_shooter_controllers::Controller::Controller
Controller()=default
rm_shooter_controllers::Controller::enter_ready_
bool enter_ready_
Definition: standard.h:129
rm_shooter_controllers::Controller::cmd_
rm_msgs::ShootCmd cmd_
Definition: standard.h:151
rm_shooter_controllers::Controller::count_
int count_
Definition: standard.h:124
rm_shooter_controllers::Controller::update
void update(const ros::Time &time, const ros::Duration &period) override
Definition: standard.cpp:145
rm_shooter_controllers::Controller::STOP
@ STOP
Definition: standard.h:142
rm_shooter_controllers::Controller::config_
Config config_
Definition: standard.h:148
rm_shooter_controllers::Controller::cmd_rt_buffer_
realtime_tools::RealtimeBuffer< rm_msgs::ShootCmd > cmd_rt_buffer_
Definition: standard.h:150
rm_shooter_controllers::Config::block_speed
double block_speed
Definition: standard.h:121
joint_velocity_controller.h
rm_shooter_controllers::Controller::wheel_speed_drop_
bool wheel_speed_drop_
Definition: standard.h:136
rm_shooter_controllers::Config::exit_push_threshold
double exit_push_threshold
Definition: standard.h:122
rm_shooter_controllers::Controller::PUSH
@ PUSH
Definition: standard.h:144
rm_shooter_controllers::Controller::friction_block_effort_
double friction_block_effort_
Definition: standard.h:133
rm_shooter_controllers::Controller::effort_joint_interface_
hardware_interface::EffortJointInterface * effort_joint_interface_
Definition: standard.h:119
rm_shooter_controllers::Controller::push
void push(const ros::Time &time, const ros::Duration &period)
Definition: standard.cpp:227
rm_shooter_controllers::Controller::ctrls_friction_
std::vector< std::vector< effort_controllers::JointVelocityController * > > ctrls_friction_
Definition: standard.h:120
rm_shooter_controllers::Controller::state_changed_
bool state_changed_
Definition: standard.h:128
rm_shooter_controllers::Controller::BLOCK
@ BLOCK
Definition: standard.h:145
rm_shooter_controllers::Controller::anti_friction_block_duty_cycle_
double anti_friction_block_duty_cycle_
Definition: standard.h:134
rm_shooter_controllers::Config::block_duration
double block_duration
Definition: standard.h:121
rm_shooter_controllers::Controller::friction_wheel_block
bool friction_wheel_block
Definition: standard.h:132
rm_shooter_controllers::Controller::commandCB
void commandCB(const rm_msgs::ShootCmdConstPtr &msg)
Definition: standard.h:112
rm_shooter_controllers::Controller::local_heat_state_pub_
std::shared_ptr< realtime_tools::RealtimePublisher< rm_msgs::LocalHeatState > > local_heat_state_pub_
Definition: standard.h:152
rm_shooter_controllers::Controller::init
bool init(hardware_interface::RobotHW *robot_hw, ros::NodeHandle &root_nh, ros::NodeHandle &controller_nh) override
Definition: standard.cpp:76
rm_shooter_controllers::Controller::freq_threshold_
double freq_threshold_
Definition: standard.h:126
rm_shooter_controllers::Controller::wheel_speed_offsets_
std::vector< std::vector< double > > wheel_speed_offsets_
Definition: standard.h:122
joint_command_interface.h
hardware_interface::RobotHW
rm_shooter_controllers::Controller::setSpeed
void setSpeed(const rm_msgs::ShootCmd &cmd)
Definition: standard.cpp:306
controller_interface::MultiInterfaceController
rm_shooter_controllers
Definition: standard.h:55
rm_shooter_controllers::Controller::state_
int state_
Definition: standard.h:147
rm_shooter_controllers::Controller::maybe_block_
bool maybe_block_
Definition: standard.h:130
hardware_interface::EffortJointInterface
rm_shooter_controllers::Controller::block
void block(const ros::Time &time, const ros::Duration &period)
Definition: standard.cpp:286
rm_shooter_controllers::Controller::last_friction_wheel_block
bool last_friction_wheel_block
Definition: standard.h:132
rm_shooter_controllers::Controller::friction_block_vel_
double friction_block_vel_
Definition: standard.h:133
rm_shooter_controllers::Controller::shoot_state_pub_
std::shared_ptr< realtime_tools::RealtimePublisher< rm_msgs::ShootState > > shoot_state_pub_
Definition: standard.h:153
rm_shooter_controllers::Config::anti_block_threshold
double anti_block_threshold
Definition: standard.h:121
joint_position_controller.h
robot_state_interface.h
rm_shooter_controllers::Controller::last_block_time_
ros::Time last_block_time_
Definition: standard.h:139
rm_shooter_controllers::Config::wheel_speed_raise_threshold
double wheel_speed_raise_threshold
Definition: standard.h:123
rm_shooter_controllers::Controller::READY
@ READY
Definition: standard.h:143
rm_shooter_controllers::Controller::reconfigCB
void reconfigCB(rm_shooter_controllers::ShooterConfig &config, uint32_t)
Definition: standard.cpp:412
effort_controllers::JointPositionController
ros::Time
rm_shooter_controllers::Controller::block_time_
ros::Time block_time_
Definition: standard.h:139
rm_shooter_controllers::Controller::normalize
void normalize()
Definition: standard.cpp:353
rm_shooter_controllers::Controller::ctrl_trigger_
effort_controllers::JointPositionController ctrl_trigger_
Definition: standard.h:121
rm_shooter_controllers::Controller
Definition: standard.h:95
rm_shooter_controllers::Controller::starting
void starting(const ros::Time &) override
Definition: standard.cpp:139
rm_shooter_controllers::Controller::stop
void stop(const ros::Time &time, const ros::Duration &period)
Definition: standard.cpp:199
rm_shooter_controllers::Controller::config_rt_buffer
realtime_tools::RealtimeBuffer< Config > config_rt_buffer
Definition: standard.h:149
rm_shooter_controllers::Config::block_effort
double block_effort
Definition: standard.h:121
rm_shooter_controllers::Config::wheel_speed_drop_threshold
double wheel_speed_drop_threshold
Definition: standard.h:123
rm_shooter_controllers::Config::extra_wheel_speed
double extra_wheel_speed
Definition: standard.h:123
ros_utilities.h
rm_shooter_controllers::Config::forward_push_threshold
double forward_push_threshold
Definition: standard.h:122
rm_shooter_controllers::Controller::judgeBulletShoot
void judgeBulletShoot(const ros::Time &time, const ros::Duration &period)
Definition: standard.cpp:370
rm_shooter_controllers::Controller::last_shoot_time_
ros::Time last_shoot_time_
Definition: standard.h:139
rm_shooter_controllers::Config::anti_block_angle
double anti_block_angle
Definition: standard.h:121
rm_shooter_controllers::Controller::wheel_speed_directions_
std::vector< std::vector< double > > wheel_speed_directions_
Definition: standard.h:123
rm_shooter_controllers::Controller::last_wheel_speed_
double last_wheel_speed_
Definition: standard.h:137
cmd
string cmd
rm_shooter_controllers::Controller::push_per_rotation_
int push_per_rotation_
Definition: standard.h:124
rm_shooter_controllers::Config
Definition: standard.h:88
rm_shooter_controllers::Controller::anti_friction_block_vel_
double anti_friction_block_vel_
Definition: standard.h:134
rm_shooter_controllers::Controller::ready
void ready(const ros::Duration &period)
Definition: standard.cpp:216
ros::Duration
ros::NodeHandle
ros::Subscriber
rm_shooter_controllers::Controller::wheel_speed_raise_
bool wheel_speed_raise_
Definition: standard.h:136
rm_shooter_controllers::Controller::has_shoot_
bool has_shoot_
Definition: standard.h:135
rm_shooter_controllers::Controller::d_srv_
dynamic_reconfigure::Server< rm_shooter_controllers::ShooterConfig > * d_srv_
Definition: standard.h:155
multi_interface_controller.h


rm_shooter_controllers
Author(s): Qiayuan Liao
autogenerated on Sun May 4 2025 02:57:27