mirror of
https://gitlab.com/obbart/universal_robots_ros_driver.git
synced 2026-04-10 10:00:48 +02:00
reset controllers only on when robot program is started
This commit is contained in:
committed by
Felix Mauch
parent
b2503352a9
commit
ad129da4c1
@@ -67,6 +67,8 @@ public:
|
|||||||
|
|
||||||
void handleRobotProgramState(bool program_running);
|
void handleRobotProgramState(bool program_running);
|
||||||
|
|
||||||
|
bool shouldResetControllers();
|
||||||
|
|
||||||
protected:
|
protected:
|
||||||
/*!
|
/*!
|
||||||
* \brief Transforms force-torque measurements reported from the robot from base to tool frame
|
* \brief Transforms force-torque measurements reported from the robot from base to tool frame
|
||||||
@@ -103,6 +105,8 @@ protected:
|
|||||||
std::string tcp_link_;
|
std::string tcp_link_;
|
||||||
bool robot_program_running_;
|
bool robot_program_running_;
|
||||||
ros::Publisher program_state_pub_;
|
ros::Publisher program_state_pub_;
|
||||||
|
|
||||||
|
bool controller_reset_necessary_;
|
||||||
};
|
};
|
||||||
|
|
||||||
} // namespace ur_driver
|
} // namespace ur_driver
|
||||||
|
|||||||
@@ -344,10 +344,27 @@ bool HardwareInterface ::isRobotProgramRunning() const
|
|||||||
|
|
||||||
void HardwareInterface ::handleRobotProgramState(bool program_running)
|
void HardwareInterface ::handleRobotProgramState(bool program_running)
|
||||||
{
|
{
|
||||||
|
if (robot_program_running_ == false && program_running)
|
||||||
|
{
|
||||||
|
controller_reset_necessary_ = true;
|
||||||
|
}
|
||||||
robot_program_running_ = program_running;
|
robot_program_running_ = program_running;
|
||||||
std_msgs::Bool msg;
|
std_msgs::Bool msg;
|
||||||
msg.data = robot_program_running_;
|
msg.data = robot_program_running_;
|
||||||
program_state_pub_.publish(msg);
|
program_state_pub_.publish(msg);
|
||||||
}
|
}
|
||||||
|
|
||||||
|
bool HardwareInterface ::shouldResetControllers()
|
||||||
|
{
|
||||||
|
if (controller_reset_necessary_)
|
||||||
|
{
|
||||||
|
controller_reset_necessary_ = false;
|
||||||
|
return true;
|
||||||
|
}
|
||||||
|
else
|
||||||
|
{
|
||||||
|
return false;
|
||||||
|
}
|
||||||
|
}
|
||||||
|
|
||||||
} // namespace ur_driver
|
} // namespace ur_driver
|
||||||
|
|||||||
@@ -141,8 +141,7 @@ int main(int argc, char** argv)
|
|||||||
period.fromSec(std::chrono::duration_cast<std::chrono::duration<double>>(stopwatch_now - stopwatch_last).count());
|
period.fromSec(std::chrono::duration_cast<std::chrono::duration<double>>(stopwatch_now - stopwatch_last).count());
|
||||||
stopwatch_last = stopwatch_now;
|
stopwatch_last = stopwatch_now;
|
||||||
|
|
||||||
// cm.update(timestamp, period, !g_hw_interface->isRobotProgramRunning());
|
cm.update(timestamp, period, g_hw_interface->shouldResetControllers());
|
||||||
cm.update(timestamp, period);
|
|
||||||
|
|
||||||
g_hw_interface->write(timestamp, period);
|
g_hw_interface->write(timestamp, period);
|
||||||
// if (!control_rate.sleep())
|
// if (!control_rate.sleep())
|
||||||
|
|||||||
Reference in New Issue
Block a user