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 @@ -89,6 +89,7 @@ class Controller : public controller_interface::MultiInterfaceController<hardwar
std::vector<std::vector<effort_controllers::JointVelocityController*>> ctrls_friction_;
effort_controllers::JointPositionController ctrl_trigger_;
std::vector<std::vector<double>> wheel_speed_offsets_;
std::vector<std::vector<double>> wheel_speed_directions_;
int push_per_rotation_{}, count_{};
double push_wheel_speed_threshold_{};
double freq_threshold_{};
Expand Down
31 changes: 19 additions & 12 deletions rm_shooter_controllers/src/standard.cpp
Original file line number Diff line number Diff line change
Expand Up @@ -77,16 +77,20 @@ bool Controller::init(hardware_interface::RobotHW* robot_hw, ros::NodeHandle& ro

XmlRpc::XmlRpcValue friction;
double wheel_speed_offset;
double wheel_speed_direction;
effort_joint_interface_ = robot_hw->get<hardware_interface::EffortJointInterface>();
controller_nh.getParam("friction", friction);
for (const auto& its : friction)
{
std::vector<double> wheel_speed_offset_temp;
std::vector<double> wheel_speed_direction_temp;
std::vector<effort_controllers::JointVelocityController*> ctrl_frictions;
for (const auto& it : its.second)
{
ros::NodeHandle nh = ros::NodeHandle(controller_nh, "friction/" + its.first + "/" + it.first);
wheel_speed_offset_temp.push_back(nh.getParam("wheel_speed_offset", wheel_speed_offset) ? wheel_speed_offset : 0.);
wheel_speed_direction_temp.push_back(
nh.getParam("wheel_speed_direction", wheel_speed_direction) ? wheel_speed_direction : 1.);
effort_controllers::JointVelocityController* ctrl_friction = new effort_controllers::JointVelocityController;
if (ctrl_friction->init(effort_joint_interface_, nh))
ctrl_frictions.push_back(ctrl_friction);
Expand All @@ -95,6 +99,7 @@ bool Controller::init(hardware_interface::RobotHW* robot_hw, ros::NodeHandle& ro
}
ctrls_friction_.push_back(ctrl_frictions);
wheel_speed_offsets_.push_back(wheel_speed_offset_temp);
wheel_speed_directions_.push_back(wheel_speed_direction_temp);
}
ros::NodeHandle nh_trigger = ros::NodeHandle(controller_nh, "trigger");
return ctrl_trigger_.init(effort_joint_interface_, nh_trigger);
Expand Down Expand Up @@ -194,12 +199,13 @@ void Controller::push(const ros::Time& time, const ros::Duration& period)
ROS_INFO("[Shooter] Enter PUSH");
}
bool wheel_speed_ready = true;
for (auto& ctrl_frictions : ctrls_friction_)
for (size_t i = 0; i < ctrls_friction_.size(); i++)
{
for (auto& ctrl_friction : ctrl_frictions)
for (size_t j = 0; j < ctrls_friction_[i].size(); j++)
{
if (ctrl_friction->joint_.getVelocity() < push_wheel_speed_threshold_ * ctrl_friction->command_ ||
ctrl_friction->joint_.getVelocity() <= M_PI)
if (wheel_speed_directions_[i][j] * ctrls_friction_[i][j]->joint_.getVelocity() <
push_wheel_speed_threshold_ * ctrls_friction_[i][j]->command_ ||
wheel_speed_directions_[i][j] * ctrls_friction_[i][j]->joint_.getVelocity() <= M_PI)
wheel_speed_ready = false;
}
}
Expand Down Expand Up @@ -268,12 +274,12 @@ void Controller::setSpeed(const rm_msgs::ShootCmd& cmd)
{
static int friction_block_count = 0;
bool friction_wheel_block = false;
for (auto& ctrl_frictions : ctrls_friction_)
for (size_t i = 0; i < ctrls_friction_.size(); i++)
{
for (auto& ctrl_friction : ctrl_frictions)
for (size_t j = 0; j < ctrls_friction_[i].size(); j++)
{
if (ctrl_friction->joint_.getVelocity() <= friction_block_vel_ &&
abs(ctrl_friction->joint_.getEffort()) >= friction_block_effort_ && cmd.wheel_speed != 0)
if (wheel_speed_directions_[i][j] * ctrls_friction_[i][j]->joint_.getVelocity() <= friction_block_vel_ &&
abs(ctrls_friction_[i][j]->joint_.getEffort()) >= friction_block_effort_ && cmd.wheel_speed != 0)
friction_wheel_block = true;
}
}
Expand All @@ -283,7 +289,8 @@ void Controller::setSpeed(const rm_msgs::ShootCmd& cmd)
{
for (size_t j = 0; j < ctrls_friction_[i].size(); j++)
{
ctrls_friction_[i][j]->setCommand(cmd_.wheel_speed + config_.extra_wheel_speed + wheel_speed_offsets_[i][j]);
ctrls_friction_[i][j]->setCommand(wheel_speed_directions_[i][j] *
(cmd_.wheel_speed + config_.extra_wheel_speed + wheel_speed_offsets_[i][j]));
}
}
}
Expand All @@ -292,11 +299,11 @@ void Controller::setSpeed(const rm_msgs::ShootCmd& cmd)
double command = (friction_block_count <= static_cast<int>(anti_friction_block_duty_cycle_ * 1000)) ?
anti_friction_block_vel_ :
0.;
for (auto& ctrl_frictions : ctrls_friction_)
for (size_t i = 0; i < ctrls_friction_.size(); i++)
{
for (auto& ctrl_friction : ctrl_frictions)
for (size_t j = 0; j < ctrls_friction_[i].size(); j++)
{
ctrl_friction->setCommand(command);
ctrls_friction_[i][j]->setCommand(command);
}
}
friction_block_count = (friction_block_count + 1) % 1000;
Expand Down
Loading