Skip to content
Open
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
Original file line number Diff line number Diff line change
@@ -1,33 +1,25 @@
#ifndef KUKA_RSI_HARDWARE_INTERFACE_WITH_FTS
#define KUKA_RSI_HARDWARE_INTERFACE_WITH_FTS

#include <force_controllers/force_controller.h>
#include <boost/shared_ptr.hpp>

#include <kuka_rsi_hw_interface/kuka_hardware_interface.h>

#include <force_torque_sensor/force_torque_sensor_handle.h>
#include <hardware_interface/force_torque_sensor_interface.h>
#include <kuka_rsi_hw_interface/kuka_hardware_interface.h>
#include <ros/console.h>
#include <boost/shared_ptr.hpp>

namespace kuka_rsi_hw_interface
{

class KukaHardwareInterfaceWithFTS : public KukaHardwareInterface
{
force_torque_control::ForceTorqueControllerInterface ftc_interface_;
// ForceTorqueSensorHandle* ftsh_;
boost::shared_ptr<hardware_interface::ForceTorqueSensorHandle> ftsh_;
ros::NodeHandle nh_;

std::string fts_name;
std::string fts_sensor_frame;
std::string fts_transform_frame;

public:
KukaHardwareInterfaceWithFTS(ros::NodeHandle nh);
// ~KukaHardwareInterfaceWithFTS();

void handleInit();
};
namespace kuka_rsi_hw_interface {

class KukaHardwareInterfaceWithFTS : public KukaHardwareInterface {

hardware_interface::ForceTorqueSensorInterface fts_interface_;
boost::shared_ptr<hardware_interface::ForceTorqueSensorHandle> ftsh_;

public:

explicit KukaHardwareInterfaceWithFTS(ros::NodeHandle nh);

};
} // namespace kuka_rsi_hw_interface

#endif
53 changes: 12 additions & 41 deletions kuka_rsi_hw_interface/src/kuka_hardware_interface_with_fts.cpp
Original file line number Diff line number Diff line change
@@ -1,47 +1,18 @@


#include <kuka_rsi_hw_interface/kuka_hardware_interface_with_fts.h>

namespace kuka_rsi_hw_interface
{
KukaHardwareInterfaceWithFTS::KukaHardwareInterfaceWithFTS(ros::NodeHandle nh) : KukaHardwareInterface(nh)
{
if( ros::console::set_logger_level(ROSCONSOLE_DEFAULT_NAME, ros::console::levels::Info) )
namespace kuka_rsi_hw_interface {

KukaHardwareInterfaceWithFTS::KukaHardwareInterfaceWithFTS(ros::NodeHandle nh) : KukaHardwareInterface(nh) {
if (ros::console::set_logger_level(ROSCONSOLE_DEFAULT_NAME, ros::console::levels::Info))
ros::console::notifyLoggerLevelsChanged();
nh_ = nh;
nh_.param<std::string>("/fts/FTS/name", fts_name, "fts_sensor_name");
nh_.param<std::string>("/fts/Node/transform_frame", fts_transform_frame, "fts_base_link");
ROS_DEBUG_STREAM("try to register the force torque controller interface to simulation env.");
registerInterface(&ftc_interface_);
ROS_DEBUG_STREAM("successfully registered force torque controller interface");

// create a robot handle for kr5, and attach the fake sensor handle
ROS_DEBUG_STREAM("creating ForceTorqueControllerHandle");
force_torque_control::ForceTorqueControllerHandle handle("kuka_fts_controller_handle");

ROS_DEBUG_STREAM("creating ForceTorqueSensorHandle");
ftsh_.reset(new force_torque_sensor::ForceTorqueSensorHandle(nh_, fts_name, fts_transform_frame));
ROS_INFO_STREAM("ForceTorqueSensorHandle created!");

handle.addHandle(*ftsh_);
ROS_INFO("force torque sensor handle added");

std::vector<std::string> pos_names = position_joint_interface_.getNames();
for(size_t i = 0; i < pos_names.size(); i ++)
handle.addPosHandle(position_joint_interface_.getHandle(pos_names[i]));
ROS_DEBUG_STREAM("add position handle");
// TODO add velocity interface to kuka_hardware_interface.h
std::vector<std::string> vel_names = velocity_joint_interface_.getNames();
for(size_t i = 0; i < vel_names.size(); i ++)
handle.addVelHandle(velocity_joint_interface_.getHandle(vel_names[i]));
ROS_DEBUG_STREAM("add velocity handle");
// // when effort interface is supported: uncomment
// std::vector<std::string> eff_names = eff_interface_.getNames();
// for(size_t i = 0; i < eff_names.size(); i ++)
// handle.addPosHandle(eff_interface_.getHandle(eff_names[i]));
std::string fts_name, fts_transform_frame;
nh.param<std::string>("/fts/FTS/name", fts_name, "fts_sensor_name");
nh.param<std::string>("/fts/Node/transform_frame", fts_transform_frame, "fts_base_link");

ftc_interface_.registerHandle(handle);
ROS_INFO("register handle to ftc interface");
}
ftsh_.reset(new force_torque_sensor::ForceTorqueSensorHandle(nh, fts_name, fts_transform_frame));

} // namespace kuka_rsi_hw_interface
fts_interface_.registerHandle(*ftsh_);
registerInterface(&fts_interface_);
}
}