Class JoystickController

Inheritance Relationships

Base Type

  • public controller_interface::ControllerInterface

Class Documentation

class JoystickController : public controller_interface::ControllerInterface

Public Functions

JOYSTICK_CONTROLLER_PUBLIC JoystickController()
JOYSTICK_CONTROLLER_PUBLIC controller_interface::InterfaceConfiguration command_interface_configuration () const override
JOYSTICK_CONTROLLER_PUBLIC controller_interface::InterfaceConfiguration state_interface_configuration () const override
JOYSTICK_CONTROLLER_PUBLIC controller_interface::return_type update (const rclcpp::Time &time, const rclcpp::Duration &period) override
JOYSTICK_CONTROLLER_PUBLIC controller_interface::CallbackReturn on_init () override
JOYSTICK_CONTROLLER_PUBLIC controller_interface::CallbackReturn on_configure (const rclcpp_lifecycle::State &previous_state) override
JOYSTICK_CONTROLLER_PUBLIC controller_interface::CallbackReturn on_activate (const rclcpp_lifecycle::State &previous_state) override
JOYSTICK_CONTROLLER_PUBLIC controller_interface::CallbackReturn on_deactivate (const rclcpp_lifecycle::State &previous_state) override
JOYSTICK_CONTROLLER_PUBLIC controller_interface::CallbackReturn on_cleanup (const rclcpp_lifecycle::State &previous_state) override
JOYSTICK_CONTROLLER_PUBLIC controller_interface::CallbackReturn on_error (const rclcpp_lifecycle::State &previous_state) override
JOYSTICK_CONTROLLER_PUBLIC controller_interface::CallbackReturn on_shutdown (const rclcpp_lifecycle::State &previous_state) override

Protected Functions

void joint_states_callback(const sensor_msgs::msg::JointState::SharedPtr msg)
double normalize_joystick_value(double raw_adc, bool is_tact_switch) const
std::vector<double> read_and_normalize_sensor_values(size_t sensor_idx) const
void update_joystick_values(const std::string &sensor_name, const std::vector<double> &normalized_values, JoystickValues &joystick_values, bool &left_tact_pressed, bool &right_tact_pressed) const
void update_last_active_positions(const std::vector<std::string> &controlled_joints)
std::vector<double> calculate_joint_positions(const std::vector<std::string> &controlled_joints, const std::vector<double> &normalized_values, const std::string &sensor_name, bool swerve_mode, const JoystickValues &joystick_values) const
void publish_joint_trajectory(const std::vector<std::string> &controlled_joints, const std::vector<double> &positions, const std::string &sensor_name)
void publish_cmd_vel(bool swerve_mode, const JoystickValues &joystick_values)
void publish_joystick_values()
void handle_tact_switches(bool left_tact_pressed, bool right_tact_pressed, const rclcpp::Time &current_time)

Protected Attributes

std::vector<std::string> sensorxel_joy_names_
std::vector<std::string> state_interface_types_ = {"JOYSTICK X VALUE", "JOYSTICK Y VALUE", "JOYSTICK TACT SWITCH"}
size_t n_sensorxel_joys_ = 0
std::vector<std::vector<double>> sensorxel_joy_values_
std::vector<std::vector<std::reference_wrapper<hardware_interface::LoanedStateInterface>>> joint_state_interface_
sensor_msgs::msg::JointState current_joint_states_
bool was_active_ = false
bool has_joint_states_ = false
std::map<std::string, std::vector<std::string>> sensor_controlled_joints_
std::map<std::string, std::vector<std::string>> sensor_reverse_interfaces_
std::map<std::string, std::string> sensor_joint_trajectory_topic_
std::map<std::string, std::vector<double>> sensor_last_active_positions_
std::map<std::string, rclcpp::Publisher<trajectory_msgs::msg::JointTrajectory>::SharedPtr> sensor_joint_trajectory_publisher_
std::map<std::string, rclcpp::Publisher<std_msgs::msg::Float64MultiArray>::SharedPtr> sensorxel_joy_publisher_
std::map<std::string, double> sensor_jog_scale_
rclcpp::Subscription<sensor_msgs::msg::JointState>::SharedPtr joint_states_subscriber_
std::shared_ptr<ParamListener> param_listener_
Params params_
rclcpp::Publisher<std_msgs::msg::String>::SharedPtr mode_pub_
std::string current_mode_ = "arm_control"
bool prev_tact_switch_ = false
bool prev_right_tact_switch_ = false
bool prev_left_tact_switch_ = false
bool both_pressed_flag_ = false
rclcpp::Time left_tact_press_start_time_
rclcpp::Time right_tact_press_start_time_
bool left_tact_long_press_triggered_ = false
bool right_tact_long_press_triggered_ = false
rclcpp::Publisher<geometry_msgs::msg::Twist>::SharedPtr cmd_vel_pub_
rclcpp::Publisher<std_msgs::msg::String>::SharedPtr tact_trigger_pub_