Skip to content
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 @@ -86,9 +86,9 @@ class Controller : public controller_interface::MultiInterfaceController<hardwar
void reconfigCB(rm_shooter_controllers::ShooterConfig& config, uint32_t /*level*/);

hardware_interface::EffortJointInterface* effort_joint_interface_{};
std::vector<effort_controllers::JointVelocityController*> ctrls_friction_l_, ctrls_friction_r_;
std::vector<effort_controllers::JointVelocityController*> ctrls_friction_l_, ctrls_friction_m_, ctrls_friction_r_;
effort_controllers::JointPositionController ctrl_trigger_;
std::vector<double> wheel_speed_offset_l_, wheel_speed_offset_r_;
std::vector<double> wheel_speed_offset_l_, wheel_speed_offset_m_, wheel_speed_offset_r_;
int push_per_rotation_{}, count_{};
double push_wheel_speed_threshold_{};
double freq_threshold_{};
Expand Down
35 changes: 34 additions & 1 deletion rm_shooter_controllers/src/standard.cpp
Original file line number Diff line number Diff line change
Expand Up @@ -76,8 +76,9 @@ bool Controller::init(hardware_interface::RobotHW* robot_hw, ros::NodeHandle& ro
d_srv_->setCallback(cb);

effort_joint_interface_ = robot_hw->get<hardware_interface::EffortJointInterface>();
XmlRpc::XmlRpcValue friction_left, friction_right;
XmlRpc::XmlRpcValue friction_left, friction_mid, friction_right;
controller_nh.getParam("friction_left", friction_left);
controller_nh.getParam("friction_mid", friction_mid);
controller_nh.getParam("friction_right", friction_right);
double wheel_speed_offset;
for (const auto& it : friction_left)
Expand All @@ -90,6 +91,16 @@ bool Controller::init(hardware_interface::RobotHW* robot_hw, ros::NodeHandle& ro
else
return false;
}
for (const auto& it : friction_mid)
{
ros::NodeHandle nh = ros::NodeHandle(controller_nh, "friction_mid/" + it.first);
wheel_speed_offset_m_.push_back(nh.getParam("wheel_speed_offset", wheel_speed_offset) ? wheel_speed_offset : 0.);
effort_controllers::JointVelocityController* ctrl_friction_m = new effort_controllers::JointVelocityController;
if (ctrl_friction_m->init(effort_joint_interface_, nh))
ctrls_friction_m_.push_back(ctrl_friction_m);
else
return false;
}
for (const auto& it : friction_right)
{
ros::NodeHandle nh = ros::NodeHandle(controller_nh, "friction_right/" + it.first);
Expand Down Expand Up @@ -155,6 +166,8 @@ void Controller::update(const ros::Time& time, const ros::Duration& period)
}
for (auto& ctrl_friction_l : ctrls_friction_l_)
ctrl_friction_l->update(time, period);
for (auto& ctrl_friction_m : ctrls_friction_m_)
ctrl_friction_m->update(time, period);
for (auto& ctrl_friction_r : ctrls_friction_r_)
ctrl_friction_r->update(time, period);
ctrl_trigger_.update(time, period);
Expand All @@ -169,6 +182,8 @@ void Controller::stop(const ros::Time& time, const ros::Duration& period)

for (auto& ctrl_friction_l : ctrls_friction_l_)
ctrl_friction_l->setCommand(0.);
for (auto& ctrl_friction_m : ctrls_friction_m_)
ctrl_friction_m->setCommand(0.);
for (auto& ctrl_friction_r : ctrls_friction_r_)
ctrl_friction_r->setCommand(0.);
ctrl_trigger_.setCommand(ctrl_trigger_.joint_.getPosition());
Expand Down Expand Up @@ -200,6 +215,12 @@ void Controller::push(const ros::Time& time, const ros::Duration& period)
ctrl_friction_l->joint_.getVelocity() <= M_PI)
wheel_speed_ready = false;
}
for (auto& ctrl_friction_m : ctrls_friction_m_)
{
if (ctrl_friction_m->joint_.getVelocity() < push_wheel_speed_threshold_ * ctrl_friction_m->command_ ||
ctrl_friction_m->joint_.getVelocity() <= M_PI)
wheel_speed_ready = false;
}
for (auto& ctrl_friction_r : ctrls_friction_r_)
{
if (ctrl_friction_r->joint_.getVelocity() > push_wheel_speed_threshold_ * ctrl_friction_r->command_ ||
Expand Down Expand Up @@ -277,6 +298,12 @@ void Controller::setSpeed(const rm_msgs::ShootCmd& cmd)
abs(ctrl_friction_l->joint_.getEffort()) >= friction_block_effort_ && cmd.wheel_speed != 0)
friction_wheel_block = true;
}
for (auto& ctrl_friction_m : ctrls_friction_m_)
{
if (ctrl_friction_m->joint_.getVelocity() <= friction_block_vel_ &&
abs(ctrl_friction_m->joint_.getEffort()) >= friction_block_effort_ && cmd.wheel_speed != 0)
friction_wheel_block = true;
}
for (auto& ctrl_friction_r : ctrls_friction_r_)
{
if (ctrl_friction_r->joint_.getVelocity() >= -1.0 * friction_block_vel_ &&
Expand All @@ -287,6 +314,8 @@ void Controller::setSpeed(const rm_msgs::ShootCmd& cmd)
{
for (size_t i = 0; i < ctrls_friction_l_.size(); i++)
ctrls_friction_l_[i]->setCommand(cmd_.wheel_speed + config_.extra_wheel_speed + wheel_speed_offset_l_[i]);
for (size_t i = 0; i < ctrls_friction_m_.size(); i++)
ctrls_friction_m_[i]->setCommand(cmd_.wheel_speed + config_.extra_wheel_speed + wheel_speed_offset_m_[i]);
for (size_t i = 0; i < ctrls_friction_r_.size(); i++)
ctrls_friction_r_[i]->setCommand(-cmd_.wheel_speed - config_.extra_wheel_speed - wheel_speed_offset_r_[i]);
}
Expand All @@ -299,6 +328,10 @@ void Controller::setSpeed(const rm_msgs::ShootCmd& cmd)
{
ctrl_friction_l->setCommand(command);
}
for (auto& ctrl_friction_m : ctrls_friction_m_)
{
ctrl_friction_m->setCommand(command);
}
for (auto& ctrl_friction_r : ctrls_friction_r_)
{
ctrl_friction_r->setCommand(command);
Expand Down
Loading