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

Resolve premature controller initialization #213

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
1 change: 1 addition & 0 deletions include/ur_modern_driver/ros/controller.h
Original file line number Diff line number Diff line change
Expand Up @@ -19,6 +19,7 @@ class ROSController : private hardware_interface::RobotHW, public URRTPacketCons
ros::NodeHandle nh_;
ros::Time lastUpdate_;
controller_manager::ControllerManager controller_;
bool robot_state_received_;

// state interfaces
JointInterface joint_interface_;
Expand Down
6 changes: 6 additions & 0 deletions src/ros/controller.cpp
Original file line number Diff line number Diff line change
Expand Up @@ -3,6 +3,7 @@
ROSController::ROSController(URCommander& commander, TrajectoryFollower& follower,
std::vector<std::string>& joint_names, double max_vel_change, std::string tcp_link)
: controller_(this, nh_)
, robot_state_received_(false)
, joint_interface_(joint_names)
, wrench_interface_(tcp_link)
, position_interface_(follower, joint_interface_, joint_names)
Expand Down Expand Up @@ -81,10 +82,15 @@ void ROSController::read(RTShared& packet)
{
joint_interface_.update(packet);
wrench_interface_.update(packet);
robot_state_received_ = true;
}

bool ROSController::update()
{
// don't run controllers if we haven't received robot state yet
if (!robot_state_received_)
return true;

auto time = ros::Time::now();
auto diff = time - lastUpdate_;
lastUpdate_ = time;
Expand Down