#include <standard.h>
|
| typedef std::vector< hardware_interface::InterfaceResources > | ClaimedResources |
| |
| enum | ControllerState {
ControllerState::CONSTRUCTED,
ControllerState::INITIALIZED,
ControllerState::RUNNING,
ControllerState::STOPPED,
ControllerState::WAITING,
ControllerState::ABORTED
} |
| |
| ControllerState | state_ |
| |
| bool | initRequest (hardware_interface::RobotHW *robot_hw, ros::NodeHandle &root_nh, ros::NodeHandle &controller_nh, ClaimedResources &claimed_resources) override |
| |
| static void | clearClaims (hardware_interface::RobotHW *robot_hw) |
| |
| static void | extractInterfaceResources (hardware_interface::RobotHW *robot_hw_in, hardware_interface::RobotHW *robot_hw_out) |
| |
| static bool | hasRequiredInterfaces (hardware_interface::RobotHW *robot_hw) |
| |
| static void | populateClaimedResources (hardware_interface::RobotHW *robot_hw, ClaimedResources &claimed_resources) |
| |
| bool | allow_optional_interfaces_ |
| |
| hardware_interface::RobotHW | robot_hw_ctrl_ |
| |
Definition at line 95 of file standard.h.
◆ anonymous enum
| Enumerator |
|---|
| STOP | |
| READY | |
| PUSH | |
| BLOCK | |
Definition at line 140 of file standard.h.
◆ Controller()
| rm_shooter_controllers::Controller::Controller |
( |
| ) |
|
|
default |
◆ block()
◆ commandCB()
| void rm_shooter_controllers::Controller::commandCB |
( |
const rm_msgs::ShootCmdConstPtr & |
msg | ) |
|
|
inlineprivate |
◆ init()
◆ judgeBulletShoot()
◆ normalize()
| void Controller::normalize |
( |
| ) |
|
|
private |
◆ push()
◆ ready()
◆ reconfigCB()
| void Controller::reconfigCB |
( |
rm_shooter_controllers::ShooterConfig & |
config, |
|
|
uint32_t |
|
|
) |
| |
|
private |
◆ setSpeed()
| void Controller::setSpeed |
( |
const rm_msgs::ShootCmd & |
cmd | ) |
|
|
private |
◆ starting()
| void Controller::starting |
( |
const ros::Time & |
| ) |
|
|
overridevirtual |
◆ stop()
◆ update()
◆ anti_friction_block_duty_cycle_
| double rm_shooter_controllers::Controller::anti_friction_block_duty_cycle_ {} |
|
private |
◆ anti_friction_block_vel_
| double rm_shooter_controllers::Controller::anti_friction_block_vel_ {} |
|
private |
◆ block_time_
| ros::Time rm_shooter_controllers::Controller::block_time_ |
|
private |
◆ cmd_
| rm_msgs::ShootCmd rm_shooter_controllers::Controller::cmd_ |
|
private |
◆ cmd_rt_buffer_
◆ cmd_subscriber_
◆ config_
| Config rm_shooter_controllers::Controller::config_ {} |
|
private |
◆ config_rt_buffer
◆ count_
| int rm_shooter_controllers::Controller::count_ {} |
|
private |
◆ ctrl_trigger_
◆ ctrls_friction_
◆ d_srv_
| dynamic_reconfigure::Server<rm_shooter_controllers::ShooterConfig>* rm_shooter_controllers::Controller::d_srv_ {} |
|
private |
◆ dynamic_reconfig_initialized_
| bool rm_shooter_controllers::Controller::dynamic_reconfig_initialized_ = false |
|
private |
◆ effort_joint_interface_
◆ enter_ready_
| bool rm_shooter_controllers::Controller::enter_ready_ = false |
|
private |
◆ freq_threshold_
| double rm_shooter_controllers::Controller::freq_threshold_ {} |
|
private |
◆ friction_block_count
| int rm_shooter_controllers::Controller::friction_block_count = 0 |
|
private |
◆ friction_block_effort_
| double rm_shooter_controllers::Controller::friction_block_effort_ {} |
|
private |
◆ friction_block_vel_
| double rm_shooter_controllers::Controller::friction_block_vel_ {} |
|
private |
◆ friction_wheel_block
| bool rm_shooter_controllers::Controller::friction_wheel_block = false |
|
private |
◆ has_shoot_
| bool rm_shooter_controllers::Controller::has_shoot_ = false |
|
private |
◆ has_shoot_last_
| bool rm_shooter_controllers::Controller::has_shoot_last_ = false |
|
private |
◆ last_block_time_
| ros::Time rm_shooter_controllers::Controller::last_block_time_ |
|
private |
◆ last_friction_wheel_block
| bool rm_shooter_controllers::Controller::last_friction_wheel_block = false |
|
private |
◆ last_shoot_time_
| ros::Time rm_shooter_controllers::Controller::last_shoot_time_ |
|
private |
◆ last_wheel_speed_
| double rm_shooter_controllers::Controller::last_wheel_speed_ {} |
|
private |
◆ local_heat_state_pub_
◆ maybe_block_
| bool rm_shooter_controllers::Controller::maybe_block_ = false |
|
private |
◆ push_per_rotation_
| int rm_shooter_controllers::Controller::push_per_rotation_ {} |
|
private |
◆ push_wheel_speed_threshold_
| double rm_shooter_controllers::Controller::push_wheel_speed_threshold_ {} |
|
private |
◆ shoot_state_pub_
◆ state_
| int rm_shooter_controllers::Controller::state_ = STOP |
|
private |
◆ state_changed_
| bool rm_shooter_controllers::Controller::state_changed_ = false |
|
private |
◆ wheel_speed_directions_
| std::vector<std::vector<double> > rm_shooter_controllers::Controller::wheel_speed_directions_ |
|
private |
◆ wheel_speed_drop_
| bool rm_shooter_controllers::Controller::wheel_speed_drop_ = true |
|
private |
◆ wheel_speed_offsets_
| std::vector<std::vector<double> > rm_shooter_controllers::Controller::wheel_speed_offsets_ |
|
private |
◆ wheel_speed_raise_
| bool rm_shooter_controllers::Controller::wheel_speed_raise_ = true |
|
private |
The documentation for this class was generated from the following files: