Skip to content
New issue

Have a question about this project? Sign up for a free GitHub account to open an issue and contact its maintainers and the community.

By clicking “Sign up for GitHub”, you agree to our terms of service and privacy statement. We’ll occasionally send you account related emails.

Already on GitHub? Sign in to your account

Achieved double stage friction wheel shooting #155

Merged
merged 9 commits into from
Mar 4, 2024
Original file line number Diff line number Diff line change
Expand Up @@ -83,13 +83,18 @@ class Controller : public controller_interface::MultiInterfaceController<hardwar
void reconfigCB(rm_shooter_controllers::ShooterConfig& config, uint32_t /*level*/);

hardware_interface::EffortJointInterface* effort_joint_interface_{};
effort_controllers::JointVelocityController ctrl_friction_l_, ctrl_friction_r_;
std::vector<effort_controllers::JointVelocityController*> ctrls_friction_l_, ctrls_friction_r_;
effort_controllers::JointPositionController ctrl_trigger_;
int push_per_rotation_{};
double offset_wheel_speed_{};
double push_wheel_speed_threshold_{};
bool dynamic_reconfig_initialized_ = false;
bool state_changed_ = false;
bool maybe_block_ = false;
bool friction_left_rotate_state_ = true;
bool friction_right_rotate_state_ = true;
bool friction_left_init_state_ = false;
bool friction_right_init_state_ = false;

ros::Time last_shoot_time_, block_time_, last_block_time_;
enum
Expand Down
85 changes: 68 additions & 17 deletions rm_shooter_controllers/src/standard.cpp
Original file line number Diff line number Diff line change
Expand Up @@ -66,13 +66,31 @@ bool Controller::init(hardware_interface::RobotHW* robot_hw, ros::NodeHandle& ro
};
d_srv_->setCallback(cb);

ros::NodeHandle nh_friction_l = ros::NodeHandle(controller_nh, "friction_left");
ros::NodeHandle nh_friction_r = ros::NodeHandle(controller_nh, "friction_right");
ros::NodeHandle nh_trigger = ros::NodeHandle(controller_nh, "trigger");
effort_joint_interface_ = robot_hw->get<hardware_interface::EffortJointInterface>();
return ctrl_friction_l_.init(effort_joint_interface_, nh_friction_l) &&
ctrl_friction_r_.init(effort_joint_interface_, nh_friction_r) &&
ctrl_trigger_.init(effort_joint_interface_, nh_trigger);
XmlRpc::XmlRpcValue friction_left, friction_right;
controller_nh.getParam("friction_left", friction_left);
controller_nh.getParam("friction_right", friction_right);
for (const auto& it : friction_left)
{
ros::NodeHandle nh = ros::NodeHandle(controller_nh, "friction_left/" + it.first);
effort_controllers::JointVelocityController* ctrl_friction_l = new effort_controllers::JointVelocityController;
if (!(friction_left_init_state_ &= ctrl_friction_l->init(effort_joint_interface_, nh)))
liyixin135 marked this conversation as resolved.
Show resolved Hide resolved
ctrls_friction_l_.push_back(ctrl_friction_l);
else
return false;
}
for (const auto& it : friction_right)
{
ros::NodeHandle nh = ros::NodeHandle(controller_nh, "friction_right/" + it.first);
effort_controllers::JointVelocityController* ctrl_friction_r = new effort_controllers::JointVelocityController;
if (!(friction_right_init_state_ &= ctrl_friction_r->init(effort_joint_interface_, nh)))
ctrls_friction_r_.push_back(ctrl_friction_r);
else
return false;
}

ros::NodeHandle nh_trigger = ros::NodeHandle(controller_nh, "trigger");
return ctrl_trigger_.init(effort_joint_interface_, nh_trigger);
}

void Controller::starting(const ros::Time& /*time*/)
Expand Down Expand Up @@ -121,8 +139,14 @@ void Controller::update(const ros::Time& time, const ros::Duration& period)
shoot_state_pub_->msg_.state = state_;
shoot_state_pub_->unlockAndPublish();
}
ctrl_friction_l_.update(time, period);
ctrl_friction_r_.update(time, period);
for (auto& ctrl_friction_l : ctrls_friction_l_)
{
ctrl_friction_l->update(time, period);
}
for (auto& ctrl_friction_r : ctrls_friction_r_)
{
ctrl_friction_r->update(time, period);
}
liyixin135 marked this conversation as resolved.
Show resolved Hide resolved
ctrl_trigger_.update(time, period);
}

Expand All @@ -133,8 +157,14 @@ void Controller::stop(const ros::Time& time, const ros::Duration& period)
state_changed_ = false;
ROS_INFO("[Shooter] Enter STOP");

ctrl_friction_l_.setCommand(0.);
ctrl_friction_r_.setCommand(0.);
for (auto& ctrl_friction_l : ctrls_friction_l_)
{
ctrl_friction_l->setCommand(0.);
}
for (auto& ctrl_friction_r : ctrls_friction_r_)
{
ctrl_friction_r->setCommand(0.);
}
ctrl_trigger_.setCommand(ctrl_trigger_.joint_.getPosition());
}
}
Expand All @@ -157,11 +187,25 @@ void Controller::push(const ros::Time& time, const ros::Duration& period)
state_changed_ = false;
ROS_INFO("[Shooter] Enter PUSH");
}
if ((cmd_.wheel_speed == 0. ||
(ctrl_friction_l_.joint_.getVelocity() >= push_wheel_speed_threshold_ * ctrl_friction_l_.command_ &&
ctrl_friction_l_.joint_.getVelocity() > M_PI &&
ctrl_friction_r_.joint_.getVelocity() <= push_wheel_speed_threshold_ * ctrl_friction_r_.command_ &&
ctrl_friction_r_.joint_.getVelocity() < -M_PI)) &&
for (auto& ctrl_friction_l : ctrls_friction_l_)
{
if (ctrl_friction_l->joint_.getVelocity() < push_wheel_speed_threshold_ * ctrl_friction_l->command_ ||
ctrl_friction_l->joint_.getVelocity() <= M_PI)
{
friction_left_rotate_state_ = false;
break;
Copy link
Contributor

Choose a reason for hiding this comment

The reason will be displayed to describe this comment to others. Learn more.

break应该可以不写

Copy link
Contributor

Choose a reason for hiding this comment

The reason will be displayed to describe this comment to others. Learn more.

这咋不改,这个标志位其实可以跟下面用同一个,然后再改一下变量名吧 @liyixin135

}
}
for (auto& ctrl_friction_r : ctrls_friction_r_)
{
if (ctrl_friction_r->joint_.getVelocity() > push_wheel_speed_threshold_ * ctrl_friction_r->command_ ||
ctrl_friction_r->joint_.getVelocity() >= -M_PI)
{
friction_right_rotate_state_ = false;
break;
}
}
if ((cmd_.wheel_speed == 0. || (friction_left_rotate_state_ && friction_right_rotate_state_)) &&
(time - last_shoot_time_).toSec() >= 1. / cmd_.hz)
{ // Time to shoot!!!
if (std::fmod(std::abs(ctrl_trigger_.command_struct_.position_ - ctrl_trigger_.getPosition()), 2. * M_PI) <
Expand Down Expand Up @@ -219,8 +263,15 @@ void Controller::block(const ros::Time& time, const ros::Duration& period)

void Controller::setSpeed(const rm_msgs::ShootCmd& cmd)
{
ctrl_friction_l_.setCommand(cmd_.wheel_speed + config_.extra_wheel_speed);
ctrl_friction_r_.setCommand(-cmd_.wheel_speed - config_.extra_wheel_speed);
for (size_t i = 0; i < ctrls_friction_l_.size(); i++)
{
if (i == 1)
offset_wheel_speed_ = 220;
else
offset_wheel_speed_ = 0;
ctrls_friction_l_[i]->setCommand(cmd_.wheel_speed + config_.extra_wheel_speed - offset_wheel_speed_);
ctrls_friction_r_[i]->setCommand(-cmd_.wheel_speed - config_.extra_wheel_speed + offset_wheel_speed_);
}
liyixin135 marked this conversation as resolved.
Show resolved Hide resolved
}

void Controller::normalize()
Expand Down
Loading