|
moveit2
The MoveIt Motion Planning Framework for ROS 2.
|
#include <sensor_msgs/msg/joy.hpp>#include <geometry_msgs/msg/twist_stamped.hpp>#include <control_msgs/msg/joint_jog.hpp>#include <std_srvs/srv/trigger.hpp>#include <moveit_msgs/msg/planning_scene.hpp>#include <rclcpp/client.hpp>#include <rclcpp/experimental/buffers/intra_process_buffer.hpp>#include <rclcpp/node.hpp>#include <rclcpp/publisher.hpp>#include <rclcpp/qos.hpp>#include <rclcpp/qos_event.hpp>#include <rclcpp/subscription.hpp>#include <rclcpp/time.hpp>#include <rclcpp/utilities.hpp>#include <thread>#include <rclcpp_components/register_node_macro.hpp>
Go to the source code of this file.
Classes | |
| class | moveit_servo::JoyToServoPub |
Namespaces | |
| moveit_servo | |
Enumerations | |
| enum | Axis { LEFT_STICK_X = 0 , LEFT_STICK_Y = 1 , LEFT_TRIGGER = 2 , RIGHT_STICK_X = 3 , RIGHT_STICK_Y = 4 , RIGHT_TRIGGER = 5 , D_PAD_X = 6 , D_PAD_Y = 7 } |
| enum | Button { A = 0 , B = 1 , X = 2 , Y = 3 , LEFT_BUMPER = 4 , RIGHT_BUMPER = 5 , CHANGE_VIEW = 6 , MENU = 7 , HOME = 8 , LEFT_STICK_CLICK = 9 , RIGHT_STICK_CLICK = 10 } |
Functions | |
| bool | convertJoyToCmd (const std::vector< float > &axes, const std::vector< int > &buttons, std::unique_ptr< geometry_msgs::msg::TwistStamped > &twist, std::unique_ptr< control_msgs::msg::JointJog > &joint) |
| // This converts a joystick axes and buttons array to a TwistStamped or JointJog message More... | |
| void | updateCmdFrame (std::string &frame_name, const std::vector< int > &buttons) |
| // This should update the frame_to_publish_ as needed for changing command frame via controller More... | |
Variables | |
| const std::string | JOY_TOPIC = "/joy" |
| const std::string | TWIST_TOPIC = "/servo_node/delta_twist_cmds" |
| const std::string | JOINT_TOPIC = "/servo_node/delta_joint_cmds" |
| const std::string | EEF_FRAME_ID = "panda_hand" |
| const std::string | BASE_FRAME_ID = "panda_link0" |
| std::map< Axis, double > | AXIS_DEFAULTS = { { LEFT_TRIGGER, 1.0 }, { RIGHT_TRIGGER, 1.0 } } |
| std::map< Button, double > | BUTTON_DEFAULTS |
| enum Axis |
| Enumerator | |
|---|---|
| LEFT_STICK_X | |
| LEFT_STICK_Y | |
| LEFT_TRIGGER | |
| RIGHT_STICK_X | |
| RIGHT_STICK_Y | |
| RIGHT_TRIGGER | |
| D_PAD_X | |
| D_PAD_Y | |
Definition at line 66 of file joystick_servo_example.cpp.
| enum Button |
| Enumerator | |
|---|---|
| A | |
| B | |
| X | |
| Y | |
| LEFT_BUMPER | |
| RIGHT_BUMPER | |
| CHANGE_VIEW | |
| MENU | |
| HOME | |
| LEFT_STICK_CLICK | |
| RIGHT_STICK_CLICK | |
Definition at line 77 of file joystick_servo_example.cpp.
| bool convertJoyToCmd | ( | const std::vector< float > & | axes, |
| const std::vector< int > & | buttons, | ||
| std::unique_ptr< geometry_msgs::msg::TwistStamped > & | twist, | ||
| std::unique_ptr< control_msgs::msg::JointJog > & | joint | ||
| ) |
// This converts a joystick axes and buttons array to a TwistStamped or JointJog message
| axes | The vector of continuous controller joystick axes |
| buttons | The vector of discrete controller button values |
| twist | A TwistStamped message to update in prep for publishing |
| joint | A JointJog message to update in prep for publishing |
Definition at line 106 of file joystick_servo_example.cpp.

| void updateCmdFrame | ( | std::string & | frame_name, |
| const std::vector< int > & | buttons | ||
| ) |
// This should update the frame_to_publish_ as needed for changing command frame via controller
| frame_name | Set the command frame to this |
| buttons | The vector of discrete controller button values |
Definition at line 150 of file joystick_servo_example.cpp.

| std::map<Axis, double> AXIS_DEFAULTS = { { LEFT_TRIGGER, 1.0 }, { RIGHT_TRIGGER, 1.0 } } |
Definition at line 94 of file joystick_servo_example.cpp.
| const std::string BASE_FRAME_ID = "panda_link0" |
Definition at line 62 of file joystick_servo_example.cpp.
| std::map<Button, double> BUTTON_DEFAULTS |
Definition at line 95 of file joystick_servo_example.cpp.
| const std::string EEF_FRAME_ID = "panda_hand" |
Definition at line 61 of file joystick_servo_example.cpp.
| const std::string JOINT_TOPIC = "/servo_node/delta_joint_cmds" |
Definition at line 60 of file joystick_servo_example.cpp.
| const std::string JOY_TOPIC = "/joy" |
Definition at line 58 of file joystick_servo_example.cpp.
| const std::string TWIST_TOPIC = "/servo_node/delta_twist_cmds" |
Definition at line 59 of file joystick_servo_example.cpp.