mirror of
https://gitlab.com/obbart/universal_robots_ros_driver.git
synced 2026-04-10 01:50:46 +02:00
Fixed issues preventing from compiling on Kinetic
This commit is contained in:
@@ -1,7 +1,6 @@
|
||||
#pragma once
|
||||
#include <controller_manager/controller_manager.h>
|
||||
#include <hardware_interface/force_torque_sensor_interface.h>
|
||||
#include <hardware_interface/internal/demangle_symbol.h>
|
||||
#include <hardware_interface/joint_command_interface.h>
|
||||
#include <hardware_interface/joint_state_interface.h>
|
||||
#include <hardware_interface/robot_hw.h>
|
||||
@@ -46,7 +45,7 @@ private:
|
||||
void registerControllereInterface(T* interface)
|
||||
{
|
||||
registerInterface(interface);
|
||||
available_interfaces_[hardware_interface::internal::demangledTypeName<typename T::parent_type>()] = interface;
|
||||
available_interfaces_[T::INTERFACE_NAME] = interface;
|
||||
}
|
||||
|
||||
void read(RTShared& state);
|
||||
|
||||
@@ -33,7 +33,9 @@ private:
|
||||
public:
|
||||
JointInterface(std::vector<std::string> &joint_names);
|
||||
void update(RTShared &packet);
|
||||
|
||||
typedef hardware_interface::JointStateInterface parent_type;
|
||||
static const std::string INTERFACE_NAME;
|
||||
};
|
||||
|
||||
class WrenchInterface : public hardware_interface::ForceTorqueSensorInterface
|
||||
@@ -44,6 +46,7 @@ public:
|
||||
WrenchInterface();
|
||||
void update(RTShared &packet);
|
||||
typedef hardware_interface::ForceTorqueSensorInterface parent_type;
|
||||
static const std::string INTERFACE_NAME;
|
||||
};
|
||||
|
||||
class VelocityInterface : public HardwareInterface, public hardware_interface::VelocityJointInterface
|
||||
@@ -59,6 +62,7 @@ public:
|
||||
virtual bool write();
|
||||
virtual void reset();
|
||||
typedef hardware_interface::VelocityJointInterface parent_type;
|
||||
static const std::string INTERFACE_NAME;
|
||||
};
|
||||
|
||||
class PositionInterface : public HardwareInterface, public hardware_interface::PositionJointInterface
|
||||
@@ -75,4 +79,5 @@ public:
|
||||
virtual void stop();
|
||||
|
||||
typedef hardware_interface::PositionJointInterface parent_type;
|
||||
static const std::string INTERFACE_NAME;
|
||||
};
|
||||
@@ -33,21 +33,23 @@ void ROSController::doSwitch(const std::list<hardware_interface::ControllerInfo>
|
||||
|
||||
for (auto const& ci : start_list)
|
||||
{
|
||||
auto ait = available_interfaces_.find(ci.hardware_interface);
|
||||
auto ait = available_interfaces_.find(ci.name);
|
||||
|
||||
if (ait == available_interfaces_.end())
|
||||
continue;
|
||||
|
||||
auto new_interface = ait->second;
|
||||
|
||||
LOG_INFO("Starting %s", ci.hardware_interface.c_str());
|
||||
LOG_INFO("Starting %s", ci.name.c_str());
|
||||
|
||||
active_interface_ = new_interface;
|
||||
new_interface->start();
|
||||
|
||||
return;
|
||||
}
|
||||
|
||||
LOG_WARN("Failed to start interface!");
|
||||
if(start_list.size() > 0)
|
||||
LOG_WARN("Failed to start interface!");
|
||||
}
|
||||
|
||||
bool ROSController::write()
|
||||
|
||||
@@ -1,6 +1,7 @@
|
||||
#include "ur_modern_driver/ros/hardware_interface.h"
|
||||
#include "ur_modern_driver/log.h"
|
||||
|
||||
const std::string JointInterface::INTERFACE_NAME = "joint_state_controller";
|
||||
JointInterface::JointInterface(std::vector<std::string> &joint_names)
|
||||
{
|
||||
for (size_t i = 0; i < 6; i++)
|
||||
@@ -16,6 +17,8 @@ void JointInterface::update(RTShared &packet)
|
||||
efforts_ = packet.i_actual;
|
||||
}
|
||||
|
||||
|
||||
const std::string WrenchInterface::INTERFACE_NAME = "force_torque_sensor_controller";
|
||||
WrenchInterface::WrenchInterface()
|
||||
{
|
||||
registerHandle(hardware_interface::ForceTorqueSensorHandle("wrench", "", tcp_.begin(), tcp_.begin() + 3));
|
||||
@@ -26,6 +29,8 @@ void WrenchInterface::update(RTShared &packet)
|
||||
tcp_ = packet.tcp_force;
|
||||
}
|
||||
|
||||
|
||||
const std::string VelocityInterface::INTERFACE_NAME = "vel_based_pos_traj_controller";
|
||||
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)
|
||||
@@ -57,6 +62,7 @@ void VelocityInterface::reset()
|
||||
}
|
||||
}
|
||||
|
||||
const std::string PositionInterface::INTERFACE_NAME = "pos_based_pos_traj_controller";
|
||||
PositionInterface::PositionInterface(TrajectoryFollower &follower,
|
||||
hardware_interface::JointStateInterface &js_interface,
|
||||
std::vector<std::string> &joint_names)
|
||||
|
||||
Reference in New Issue
Block a user