mirror of
https://gitlab.com/obbart/universal_robots_ros_driver.git
synced 2026-04-10 10:00:48 +02:00
Initialize VelocityInterface::prev_velocity_cmd_ with zeroes
This commit is contained in:
committed by
Simon Rasmussen
parent
a9530c8586
commit
64f752f744
@@ -17,7 +17,6 @@ void JointInterface::update(RTShared &packet)
|
|||||||
efforts_ = packet.i_actual;
|
efforts_ = packet.i_actual;
|
||||||
}
|
}
|
||||||
|
|
||||||
|
|
||||||
const std::string WrenchInterface::INTERFACE_NAME = "hardware_interface::ForceTorqueSensorInterface";
|
const std::string WrenchInterface::INTERFACE_NAME = "hardware_interface::ForceTorqueSensorInterface";
|
||||||
WrenchInterface::WrenchInterface(std::string tcp_link)
|
WrenchInterface::WrenchInterface(std::string tcp_link)
|
||||||
{
|
{
|
||||||
@@ -29,11 +28,10 @@ void WrenchInterface::update(RTShared &packet)
|
|||||||
tcp_ = packet.tcp_force;
|
tcp_ = packet.tcp_force;
|
||||||
}
|
}
|
||||||
|
|
||||||
|
|
||||||
const std::string VelocityInterface::INTERFACE_NAME = "hardware_interface::VelocityJointInterface";
|
const std::string VelocityInterface::INTERFACE_NAME = "hardware_interface::VelocityJointInterface";
|
||||||
VelocityInterface::VelocityInterface(URCommander &commander, hardware_interface::JointStateInterface &js_interface,
|
VelocityInterface::VelocityInterface(URCommander &commander, hardware_interface::JointStateInterface &js_interface,
|
||||||
std::vector<std::string> &joint_names, double max_vel_change)
|
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++)
|
for (size_t i = 0; i < 6; i++)
|
||||||
{
|
{
|
||||||
|
|||||||
Reference in New Issue
Block a user