Go to the documentation of this file.
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>
65 rm_control::RobotStateInterface>
81 void commandCB(
const rm_msgs::ShootCmdConstPtr& msg)
86 void reconfigCB(rm_shooter_controllers::ShooterConfig& config, uint32_t );
89 std::vector<std::vector<effort_controllers::JointVelocityController*>>
ctrls_friction_;
124 dynamic_reconfigure::Server<rm_shooter_controllers::ShooterConfig>*
d_srv_{};
double push_wheel_speed_threshold_
ros::Subscriber cmd_subscriber_
bool dynamic_reconfig_initialized_
void update(const ros::Time &time, const ros::Duration &period) override
realtime_tools::RealtimeBuffer< rm_msgs::ShootCmd > cmd_rt_buffer_
double exit_push_threshold
double friction_block_effort_
hardware_interface::EffortJointInterface * effort_joint_interface_
void push(const ros::Time &time, const ros::Duration &period)
std::vector< std::vector< effort_controllers::JointVelocityController * > > ctrls_friction_
double anti_friction_block_duty_cycle_
bool friction_wheel_block
void commandCB(const rm_msgs::ShootCmdConstPtr &msg)
std::shared_ptr< realtime_tools::RealtimePublisher< rm_msgs::LocalHeatState > > local_heat_state_pub_
bool init(hardware_interface::RobotHW *robot_hw, ros::NodeHandle &root_nh, ros::NodeHandle &controller_nh) override
std::vector< std::vector< double > > wheel_speed_offsets_
void setSpeed(const rm_msgs::ShootCmd &cmd)
void block(const ros::Time &time, const ros::Duration &period)
bool last_friction_wheel_block
double friction_block_vel_
std::shared_ptr< realtime_tools::RealtimePublisher< rm_msgs::ShootState > > shoot_state_pub_
double anti_block_threshold
ros::Time last_block_time_
double wheel_speed_raise_threshold
void reconfigCB(rm_shooter_controllers::ShooterConfig &config, uint32_t)
effort_controllers::JointPositionController ctrl_trigger_
void starting(const ros::Time &) override
void stop(const ros::Time &time, const ros::Duration &period)
realtime_tools::RealtimeBuffer< Config > config_rt_buffer
double wheel_speed_drop_threshold
double forward_push_threshold
void judgeBulletShoot(const ros::Time &time, const ros::Duration &period)
ros::Time last_shoot_time_
std::vector< std::vector< double > > wheel_speed_directions_
double anti_friction_block_vel_
void ready(const ros::Duration &period)
dynamic_reconfigure::Server< rm_shooter_controllers::ShooterConfig > * d_srv_