Forward Controller working
Now 2 states where published: gripper_gap - which is the actuall gap between the two finger plates finger_joint - which is the old angle
This commit is contained in:
parent
dc53a7326f
commit
79d1eec137
@ -1,47 +0,0 @@
|
|||||||
|
|
||||||
#ifndef ROBOTIQ_FORWARD_CONTROLLER_HPP
|
|
||||||
#define ROBOTIQ_FORWARD_CONTROLLER_HPP
|
|
||||||
|
|
||||||
#include <vector>
|
|
||||||
#include <string>
|
|
||||||
|
|
||||||
#include "controller_interface/controller_interface.hpp"
|
|
||||||
#include <rclcpp/rclcpp.hpp>
|
|
||||||
#include "rclcpp_lifecycle/lifecycle_node.hpp"
|
|
||||||
#include "hardware_interface/loaned_command_interface.hpp"
|
|
||||||
#include <hardware_interface/types/hardware_interface_type_values.hpp>
|
|
||||||
|
|
||||||
#include "robotiq_2f_msgs/msg/forward_command.hpp"
|
|
||||||
|
|
||||||
|
|
||||||
namespace robotiq_2f_controllers
|
|
||||||
{
|
|
||||||
class RobotiqForwardController : public controller_interface::ControllerInterface
|
|
||||||
{
|
|
||||||
public:
|
|
||||||
RobotiqForwardController();
|
|
||||||
controller_interface::InterfaceConfiguration command_interface_configuration() const override;
|
|
||||||
controller_interface::InterfaceConfiguration state_interface_configuration() const override;
|
|
||||||
controller_interface::return_type update(const rclcpp::Time& time, const rclcpp::Duration& period) override;
|
|
||||||
|
|
||||||
rclcpp_lifecycle::node_interfaces::LifecycleNodeInterface::CallbackReturn on_init() override;
|
|
||||||
rclcpp_lifecycle::node_interfaces::LifecycleNodeInterface::CallbackReturn on_configure(const rclcpp_lifecycle::State& previous_state) override;
|
|
||||||
rclcpp_lifecycle::node_interfaces::LifecycleNodeInterface::CallbackReturn on_activate(const rclcpp_lifecycle::State& previous_state) override;
|
|
||||||
rclcpp_lifecycle::node_interfaces::LifecycleNodeInterface::CallbackReturn on_deactivate(const rclcpp_lifecycle::State& previous_state) override;
|
|
||||||
|
|
||||||
private:
|
|
||||||
std::string joint_name_;
|
|
||||||
hardware_interface::LoanedCommandInterface position_command_;
|
|
||||||
hardware_interface::LoanedCommandInterface max_effort_command_;
|
|
||||||
hardware_interface::LoanedCommandInterface max_velocity_command_;
|
|
||||||
|
|
||||||
rclcpp::Subscription<robotiq_2f_msgs::msg::ForwardCommand>::SharedPtr command_subscriber_;
|
|
||||||
double desired_position_;
|
|
||||||
double desired_max_velocity_;
|
|
||||||
double desired_max_effort_;
|
|
||||||
|
|
||||||
void command_callback(const robotiq_2f_msgs::msg::ForwardCommand::SharedPtr msg);
|
|
||||||
|
|
||||||
};
|
|
||||||
}
|
|
||||||
#endif
|
|
@ -4,6 +4,6 @@ robotiq_2f_gripper:
|
|||||||
max_position: 0.14 # Meters (fully open)
|
max_position: 0.14 # Meters (fully open)
|
||||||
max_angle: 0.695 # radiants (closed)
|
max_angle: 0.695 # radiants (closed)
|
||||||
min_speed: 0.02 # Meters per second
|
min_speed: 0.02 # Meters per second
|
||||||
max_speed: 0.5 # Meters per second
|
max_speed: 0.15 # Meters per second
|
||||||
min_force: 20.0 # Newtons
|
min_force: 20.0 # Newtons
|
||||||
max_force: 235.0 # Newtons
|
max_force: 235.0 # Newtons
|
@ -51,9 +51,7 @@ public:
|
|||||||
isActive.store(true); // Ensure we set active before moving
|
isActive.store(true); // Ensure we set active before moving
|
||||||
if (!autoCalibrate) {
|
if (!autoCalibrate) {
|
||||||
// Simulate a calibration sequence
|
// Simulate a calibration sequence
|
||||||
move_and_wait(0, 64, 1);
|
move_and_wait(0, 255, 1);
|
||||||
move_and_wait(255, 64, 1);
|
|
||||||
move_and_wait(0, 64, 1);
|
|
||||||
}
|
}
|
||||||
}
|
}
|
||||||
|
|
||||||
@ -96,7 +94,7 @@ private:
|
|||||||
// Simulate moving towards the target position
|
// Simulate moving towards the target position
|
||||||
while (gripperPosition.load() != targetPosition) {
|
while (gripperPosition.load() != targetPosition) {
|
||||||
gripperPosition.fetch_add(step);
|
gripperPosition.fetch_add(step);
|
||||||
std::this_thread::sleep_for(std::chrono::milliseconds(100)); // Simulate time to move a step
|
std::this_thread::sleep_for(std::chrono::milliseconds(10)); // Simulate time to move a step
|
||||||
}
|
}
|
||||||
|
|
||||||
std::cout << "Reached position " << targetPosition << " with speed " << speed << " and force " << force << std::endl;
|
std::cout << "Reached position " << targetPosition << " with speed " << speed << " and force " << force << std::endl;
|
||||||
|
Loading…
Reference in New Issue
Block a user