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 #154

Closed
wants to merge 2 commits into from
Closed
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 @@ -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_;
XmlRpc::XmlRpcValue friction_left_, friction_right_;
std::vector<effort_controllers::JointVelocityController*> ctrls_friction_l_, ctrls_friction_r_;
effort_controllers::JointPositionController ctrl_trigger_;
int push_per_rotation_{};
double push_wheel_speed_threshold_{};
double offset_wheel_speed_{};
bool dynamic_reconfig_initialized_ = false;
bool state_changed_ = false;
bool maybe_block_ = false;
bool is_rotate_ = false;
bool friction_left_init_state_ = false;
bool friction_right_init_state_ = false;

ros::Time last_shoot_time_, block_time_, last_block_time_;
enum
Expand All @@ -109,4 +114,4 @@ class Controller : public controller_interface::MultiInterfaceController<hardwar
dynamic_reconfigure::Server<rm_shooter_controllers::ShooterConfig>* d_srv_{};
};

} // namespace rm_shooter_controllers
} // namespace rm_shooter_controllers
77 changes: 58 additions & 19 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);

controller_nh.getParam("friction_left", friction_left_);
controller_nh.getParam("friction_right", friction_right_);
for (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)))
ctrls_friction_l_.push_back(ctrl_friction_l);
else
return false;
}
for (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,11 @@ 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 (size_t i = 0; i < ctrls_friction_l_.size(); i++)
{
ctrls_friction_l_[i]->update(time, period);
ctrls_friction_r_[i]->update(time, period);
}
ctrl_trigger_.update(time, period);
}

Expand All @@ -133,8 +154,11 @@ 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 (size_t i = 0; i < ctrls_friction_l_.size(); i++)
{
ctrls_friction_l_[i]->setCommand(0.);
ctrls_friction_r_[i]->setCommand(0.);
}
ctrl_trigger_.setCommand(ctrl_trigger_.joint_.getPosition());
}
}
Expand All @@ -157,12 +181,20 @@ 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)) &&
(time - last_shoot_time_).toSec() >= 1. / cmd_.hz)
for (size_t i = 0; i < ctrls_friction_l_.size(); i++)
{
if (cmd_.wheel_speed == 0. ||
(ctrls_friction_l_[i]->joint_.getVelocity() >= push_wheel_speed_threshold_ * ctrls_friction_l_[i]->command_ &&
ctrls_friction_l_[i]->joint_.getVelocity() > M_PI &&
ctrls_friction_r_[i]->joint_.getVelocity() <= push_wheel_speed_threshold_ * ctrls_friction_r_[i]->command_ &&
ctrls_friction_r_[i]->joint_.getVelocity() < -M_PI))
{
is_rotate_ = true;
}
else
is_rotate_ = false;
}
if (is_rotate_ && (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) <
config_.forward_push_threshold)
Expand Down Expand Up @@ -219,8 +251,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_);
}
}

void Controller::normalize()
Expand Down Expand Up @@ -260,4 +299,4 @@ void Controller::reconfigCB(rm_shooter_controllers::ShooterConfig& config, uint3

} // namespace rm_shooter_controllers

PLUGINLIB_EXPORT_CLASS(rm_shooter_controllers::Controller, controller_interface::ControllerBase)
PLUGINLIB_EXPORT_CLASS(rm_shooter_controllers::Controller, controller_interface::ControllerBase)
Loading