1
0
mirror of https://gitlab.com/obbart/universal_robots_ros_driver.git synced 2026-04-09 17:40:47 +02:00

Initialize VelocityInterface::prev_velocity_cmd_ with zeroes

This commit is contained in:
Miguel Prada
2018-04-23 16:38:10 +02:00
committed by Simon Rasmussen
parent a9530c8586
commit 64f752f744

View File

@@ -17,7 +17,6 @@ void JointInterface::update(RTShared &packet)
efforts_ = packet.i_actual;
}
const std::string WrenchInterface::INTERFACE_NAME = "hardware_interface::ForceTorqueSensorInterface";
WrenchInterface::WrenchInterface(std::string tcp_link)
{
@@ -29,11 +28,10 @@ void WrenchInterface::update(RTShared &packet)
tcp_ = packet.tcp_force;
}
const std::string VelocityInterface::INTERFACE_NAME = "hardware_interface::VelocityJointInterface";
VelocityInterface::VelocityInterface(URCommander &commander, hardware_interface::JointStateInterface &js_interface,
std::vector<std::string> &joint_names, double max_vel_change)
: commander_(commander), max_vel_change_(max_vel_change)
: commander_(commander), max_vel_change_(max_vel_change), prev_velocity_cmd_({ 0, 0, 0, 0, 0, 0 })
{
for (size_t i = 0; i < 6; i++)
{