Skip to content
Merged
Show file tree
Hide file tree
Changes from all commits
Commits
File filter

Filter by extension

Filter by extension

Conversations
Failed to load comments.
Loading
Jump to
Jump to file
Failed to load files.
Loading
Diff view
Diff view
Original file line number Diff line number Diff line change
Expand Up @@ -43,6 +43,7 @@
#include <hardware_interface/joint_command_interface.h>
#include <rm_common/hardware_interface/robot_state_interface.h>
#include <rm_common/ros_utilities.h>
#include <rm_common/filters/lp_filter.h>
#include <realtime_tools/realtime_publisher.h>
#include <dynamic_reconfigure/server.h>
#include <rm_shooter_controllers/ShooterConfig.h>
Expand Down Expand Up @@ -90,6 +91,7 @@ class Controller : public controller_interface::MultiInterfaceController<hardwar
effort_controllers::JointPositionController ctrl_trigger_;
std::vector<std::vector<double>> wheel_speed_offsets_;
std::vector<std::vector<double>> wheel_speed_directions_;
LowPassFilter* lp_filter_;
int push_per_rotation_{}, count_{};
double push_wheel_speed_threshold_{};
double freq_threshold_{};
Expand All @@ -102,8 +104,9 @@ class Controller : public controller_interface::MultiInterfaceController<hardwar
double friction_block_effort_{}, friction_block_vel_{};
double anti_friction_block_duty_cycle_{}, anti_friction_block_vel_{};
bool has_shoot_ = false, has_shoot_last_ = false;
bool wheel_speed_raise_ = true, wheel_speed_drop_ = true;
double last_wheel_speed_{};
bool wheel_speed_drop_ = true;
double last_fricition_speed_{};
double last_friction_change_speed_{};

ros::Time last_shoot_time_, block_time_, last_block_time_;
enum
Expand Down
52 changes: 19 additions & 33 deletions rm_shooter_controllers/src/standard.cpp
Original file line number Diff line number Diff line change
Expand Up @@ -101,6 +101,7 @@ bool Controller::init(hardware_interface::RobotHW* robot_hw, ros::NodeHandle& ro
wheel_speed_offsets_.push_back(wheel_speed_offset_temp);
wheel_speed_directions_.push_back(wheel_speed_direction_temp);
}
lp_filter_ = new LowPassFilter(controller_nh);
ros::NodeHandle nh_trigger = ros::NodeHandle(controller_nh, "trigger");
return ctrl_trigger_.init(effort_joint_interface_, nh_trigger);
}
Expand Down Expand Up @@ -338,45 +339,30 @@ void Controller::normalize()

void Controller::judgeBulletShoot(const ros::Time& time, const ros::Duration& period)
{
lp_filter_->input(ctrls_friction_[0][0]->joint_.getVelocity());
double friction_speed = lp_filter_->output();
double friction_change_speed = abs(friction_speed) - last_fricition_speed_;
double friction_change_speed_derivative = friction_change_speed - last_friction_change_speed_;
if (state_ != STOP)
{
if (abs(ctrls_friction_[0][0]->joint_.getVelocity()) - last_wheel_speed_ > config_.wheel_speed_raise_threshold &&
wheel_speed_drop_)
{
wheel_speed_raise_ = true;
wheel_speed_drop_ = false;
}

if (last_wheel_speed_ - abs(ctrls_friction_[0][0]->joint_.getVelocity()) > config_.wheel_speed_drop_threshold &&
abs(ctrls_friction_[0][0]->joint_.getVelocity()) > 300. && wheel_speed_raise_)
{
wheel_speed_drop_ = true;
wheel_speed_raise_ = false;
if (friction_change_speed_derivative > 0 && has_shoot_)
has_shoot_ = false;
if (friction_change_speed < -config_.wheel_speed_drop_threshold && !has_shoot_ &&
friction_change_speed_derivative < 0)
has_shoot_ = true;
}
}
double friction_change_vel = abs(ctrls_friction_[0][0]->joint_.getVelocity()) - last_wheel_speed_;
last_wheel_speed_ = abs(ctrls_friction_[0][0]->joint_.getVelocity());
count_++;
if (has_shoot_last_)
{
has_shoot_ = true;
}
has_shoot_last_ = has_shoot_;
if (count_ == 2)
last_fricition_speed_ = abs(friction_speed);
last_friction_change_speed_ = friction_change_speed;

if (local_heat_state_pub_->trylock())
{
if (local_heat_state_pub_->trylock())
{
local_heat_state_pub_->msg_.stamp = time;
local_heat_state_pub_->msg_.has_shoot = has_shoot_;
local_heat_state_pub_->msg_.friction_change_vel = friction_change_vel;
local_heat_state_pub_->unlockAndPublish();
}
has_shoot_last_ = false;
count_ = 0;
local_heat_state_pub_->msg_.stamp = time;
local_heat_state_pub_->msg_.has_shoot = has_shoot_;
local_heat_state_pub_->msg_.friction_speed = friction_speed;
local_heat_state_pub_->msg_.friction_change_speed = friction_change_speed;
local_heat_state_pub_->msg_.friction_change_speed_derivative = friction_change_speed_derivative;
local_heat_state_pub_->unlockAndPublish();
}
if (has_shoot_)
has_shoot_ = false;
}
void Controller::reconfigCB(rm_shooter_controllers::ShooterConfig& config, uint32_t /*level*/)
{
Expand Down
Loading