Skip to content
Snippets Groups Projects
Commit 4bbcd60a authored by Florian Walch's avatar Florian Walch
Browse files

Update Cartesian example controllers

parent 81f801d1
Branches
No related tags found
No related merge requests found
......@@ -20,9 +20,7 @@ class CartesianPoseExampleController
: public controller_interface::MultiInterfaceController<franka_hw::FrankaPoseCartesianInterface,
franka_hw::FrankaStateInterface> {
public:
bool init(hardware_interface::RobotHW* robot_hardware,
ros::NodeHandle& root_node_handle,
ros::NodeHandle& /* controller_node_handle */) override;
bool init(hardware_interface::RobotHW* robot_hardware, ros::NodeHandle& node_handle) override;
void starting(const ros::Time&) override;
void update(const ros::Time&, const ros::Duration& period) override;
......
......@@ -18,9 +18,7 @@ class CartesianVelocityExampleController : public controller_interface::MultiInt
franka_hw::FrankaVelocityCartesianInterface,
franka_hw::FrankaStateInterface> {
public:
bool init(hardware_interface::RobotHW* robot_hardware,
ros::NodeHandle& root_node_handle,
ros::NodeHandle& /* controller_node_handle */) override;
bool init(hardware_interface::RobotHW* robot_hardware, ros::NodeHandle& node_handle) override;
void update(const ros::Time&, const ros::Duration& period) override;
void starting(const ros::Time&) override;
void stopping(const ros::Time&) override;
......
......@@ -15,8 +15,7 @@
namespace franka_example_controllers {
bool CartesianPoseExampleController::init(hardware_interface::RobotHW* robot_hardware,
ros::NodeHandle& root_node_handle,
ros::NodeHandle& /* controller_node_handle */) {
ros::NodeHandle& node_handle) {
cartesian_pose_interface_ = robot_hardware->get<franka_hw::FrankaPoseCartesianInterface>();
if (cartesian_pose_interface_ == nullptr) {
ROS_ERROR(
......@@ -26,7 +25,7 @@ bool CartesianPoseExampleController::init(hardware_interface::RobotHW* robot_har
}
std::string arm_id;
if (!root_node_handle.getParam("arm_id", arm_id)) {
if (!node_handle.getParam("arm_id", arm_id)) {
ROS_ERROR("CartesianPoseExampleController: Could not get parameter arm_id");
return false;
}
......
......@@ -15,10 +15,9 @@
namespace franka_example_controllers {
bool CartesianVelocityExampleController::init(hardware_interface::RobotHW* robot_hardware,
ros::NodeHandle& root_node_handle,
ros::NodeHandle& /* controller_node_handle */) {
ros::NodeHandle& node_handle) {
std::string arm_id;
if (!root_node_handle.getParam("arm_id", arm_id)) {
if (!node_handle.getParam("arm_id", arm_id)) {
ROS_ERROR("CartesianVelocityExampleController: Could not get parameter arm_id");
return false;
}
......
0% Loading or .
You are about to add 0 people to the discussion. Proceed with caution.
Please register or to comment