dynamixel_workbench_controllers.h
Go to the documentation of this file.
1 /*******************************************************************************
2 * Copyright 2018 ROBOTIS CO., LTD.
3 *
4 * Licensed under the Apache License, Version 2.0 (the "License");
5 * you may not use this file except in compliance with the License.
6 * You may obtain a copy of the License at
7 *
8 * http://www.apache.org/licenses/LICENSE-2.0
9 *
10 * Unless required by applicable law or agreed to in writing, software
11 * distributed under the License is distributed on an "AS IS" BASIS,
12 * WITHOUT WARRANTIES OR CONDITIONS OF ANY KIND, either express or implied.
13 * See the License for the specific language governing permissions and
14 * limitations under the License.
15 *******************************************************************************/
16 
17 /* Authors: Taehun Lim (Darby) */
18 
19 #ifndef DYNAMIXEL_WORKBENCH_CONTROLLERS_H
20 #define DYNAMIXEL_WORKBENCH_CONTROLLERS_H
21 
22 #include <ros/ros.h>
23 
24 #include <yaml-cpp/yaml.h>
25 
26 #include <sensor_msgs/JointState.h>
27 #include <geometry_msgs/Twist.h>
28 #include <trajectory_msgs/JointTrajectory.h>
29 #include <trajectory_msgs/JointTrajectoryPoint.h>
30 
32 #include <dynamixel_workbench_msgs/DynamixelStateList.h>
33 #include <dynamixel_workbench_msgs/DynamixelCommand.h>
34 
36 
37 // SYNC_WRITE_HANDLER
38 #define SYNC_WRITE_HANDLER_FOR_GOAL_POSITION 0
39 #define SYNC_WRITE_HANDLER_FOR_GOAL_VELOCITY 1
40 
41 // SYNC_READ_HANDLER(Only for Protocol 2.0)
42 #define SYNC_READ_HANDLER_FOR_PRESENT_POSITION_VELOCITY_CURRENT 0
43 
44 // #define DEBUG
45 
46 typedef struct
47 {
48  std::string item_name;
49  int32_t value;
50 } ItemValue;
51 
53 {
54  private:
55  // ROS NodeHandle
58 
59  // ROS Parameters
60 
61  // ROS Topic Publisher
64 
65  // ROS Topic Subscriber
68 
69  // ROS Service Server
71 
72  // ROS Service Client
73 
74  // Dynamixel Workbench Parameters
76 
77  std::map<std::string, uint32_t> dynamixel_;
78  std::map<std::string, const ControlItem*> control_items_;
79  std::vector<std::pair<std::string, ItemValue>> dynamixel_info_;
80  dynamixel_workbench_msgs::DynamixelStateList dynamixel_state_list_;
81  sensor_msgs::JointState joint_state_msg_;
82  std::vector<WayPoint> pre_goal_;
83 
87 
89  double wheel_radius_;
90 
92  trajectory_msgs::JointTrajectory *jnt_tra_msg_;
93 
94  double read_period_;
95  double write_period_;
96  double pub_period_;
97 
98  bool is_moving_;
99 
100  public:
103 
104  bool initWorkbench(const std::string port_name, const uint32_t baud_rate);
105  bool getDynamixelsInfo(const std::string yaml_file);
106  bool loadDynamixels(void);
107  bool initDynamixels(void);
108  bool initControlItems(void);
109  bool initSDKHandlers(void);
110  bool getPresentPosition(std::vector<std::string> dxl_name);
111 
112  double getReadPeriod(){return read_period_;}
113  double getWritePeriod(){return write_period_;}
114  double getPublishPeriod(){return pub_period_;}
115 
116  void initPublisher(void);
117  void initSubscriber(void);
118 
119  void initServer();
120 
121  void readCallback(const ros::TimerEvent&);
122  void writeCallback(const ros::TimerEvent&);
123  void publishCallback(const ros::TimerEvent&);
124 
125  void commandVelocityCallback(const geometry_msgs::Twist::ConstPtr &msg);
126  void trajectoryMsgCallback(const trajectory_msgs::JointTrajectory::ConstPtr &msg);
127  bool dynamixelCommandMsgCallback(dynamixel_workbench_msgs::DynamixelCommand::Request &req,
128  dynamixel_workbench_msgs::DynamixelCommand::Response &res);
129 };
130 
131 #endif //DYNAMIXEL_WORKBENCH_CONTROLLERS_H
DynamixelController::dynamixel_
std::map< std::string, uint32_t > dynamixel_
Definition: dynamixel_workbench_controllers.h:77
ros::Publisher
DynamixelController::joint_states_pub_
ros::Publisher joint_states_pub_
Definition: dynamixel_workbench_controllers.h:63
DynamixelController::trajectoryMsgCallback
void trajectoryMsgCallback(const trajectory_msgs::JointTrajectory::ConstPtr &msg)
Definition: dynamixel_workbench_controllers.cpp:630
DynamixelController::trajectory_sub_
ros::Subscriber trajectory_sub_
Definition: dynamixel_workbench_controllers.h:67
DynamixelController::cmd_vel_sub_
ros::Subscriber cmd_vel_sub_
Definition: dynamixel_workbench_controllers.h:66
DynamixelWorkbench
ros.h
DynamixelController
Definition: dynamixel_workbench_controllers.h:52
DynamixelController::pub_period_
double pub_period_
Definition: dynamixel_workbench_controllers.h:96
DynamixelController::getReadPeriod
double getReadPeriod()
Definition: dynamixel_workbench_controllers.h:112
DynamixelController::dynamixel_state_list_pub_
ros::Publisher dynamixel_state_list_pub_
Definition: dynamixel_workbench_controllers.h:62
DynamixelController::readCallback
void readCallback(const ros::TimerEvent &)
Definition: dynamixel_workbench_controllers.cpp:333
JointTrajectory
Definition: trajectory_generator.h:53
DynamixelController::use_moveit_
bool use_moveit_
Definition: dynamixel_workbench_controllers.h:86
DynamixelController::jnt_tra_
JointTrajectory * jnt_tra_
Definition: dynamixel_workbench_controllers.h:91
DynamixelController::pre_goal_
std::vector< WayPoint > pre_goal_
Definition: dynamixel_workbench_controllers.h:82
DynamixelController::commandVelocityCallback
void commandVelocityCallback(const geometry_msgs::Twist::ConstPtr &msg)
Definition: dynamixel_workbench_controllers.cpp:506
ros::ServiceServer
DynamixelController::getPublishPeriod
double getPublishPeriod()
Definition: dynamixel_workbench_controllers.h:114
DynamixelController::dynamixel_info_
std::vector< std::pair< std::string, ItemValue > > dynamixel_info_
Definition: dynamixel_workbench_controllers.h:79
DynamixelController::initDynamixels
bool initDynamixels(void)
Definition: dynamixel_workbench_controllers.cpp:125
DynamixelController::dynamixelCommandMsgCallback
bool dynamixelCommandMsgCallback(dynamixel_workbench_msgs::DynamixelCommand::Request &req, dynamixel_workbench_msgs::DynamixelCommand::Response &res)
Definition: dynamixel_workbench_controllers.cpp:739
ItemValue
Definition: dynamixel_workbench_controllers.h:46
DynamixelController::dynamixel_state_list_
dynamixel_workbench_msgs::DynamixelStateList dynamixel_state_list_
Definition: dynamixel_workbench_controllers.h:80
dynamixel_workbench.h
DynamixelController::priv_node_handle_
ros::NodeHandle priv_node_handle_
Definition: dynamixel_workbench_controllers.h:57
DynamixelController::is_joint_state_topic_
bool is_joint_state_topic_
Definition: dynamixel_workbench_controllers.h:84
DynamixelController::loadDynamixels
bool loadDynamixels(void)
Definition: dynamixel_workbench_controllers.cpp:101
DynamixelController::node_handle_
ros::NodeHandle node_handle_
Definition: dynamixel_workbench_controllers.h:56
DynamixelController::initWorkbench
bool initWorkbench(const std::string port_name, const uint32_t baud_rate)
Definition: dynamixel_workbench_controllers.cpp:52
DynamixelController::getDynamixelsInfo
bool getDynamixelsInfo(const std::string yaml_file)
Definition: dynamixel_workbench_controllers.cpp:66
DynamixelController::wheel_separation_
double wheel_separation_
Definition: dynamixel_workbench_controllers.h:88
DynamixelController::initPublisher
void initPublisher(void)
Definition: dynamixel_workbench_controllers.cpp:316
DynamixelController::read_period_
double read_period_
Definition: dynamixel_workbench_controllers.h:94
ros::TimerEvent
DynamixelController::writeCallback
void writeCallback(const ros::TimerEvent &)
Definition: dynamixel_workbench_controllers.cpp:575
DynamixelController::getPresentPosition
bool getPresentPosition(std::vector< std::string > dxl_name)
Definition: dynamixel_workbench_controllers.cpp:243
DynamixelController::~DynamixelController
~DynamixelController()
Definition: dynamixel_workbench_controllers.cpp:50
DynamixelController::initControlItems
bool initControlItems(void)
Definition: dynamixel_workbench_controllers.cpp:156
DynamixelController::is_moving_
bool is_moving_
Definition: dynamixel_workbench_controllers.h:98
DynamixelController::DynamixelController
DynamixelController()
Definition: dynamixel_workbench_controllers.cpp:21
DynamixelController::is_cmd_vel_topic_
bool is_cmd_vel_topic_
Definition: dynamixel_workbench_controllers.h:85
DynamixelController::publishCallback
void publishCallback(const ros::TimerEvent &)
Definition: dynamixel_workbench_controllers.cpp:455
DynamixelController::initServer
void initServer()
Definition: dynamixel_workbench_controllers.cpp:328
DynamixelController::getWritePeriod
double getWritePeriod()
Definition: dynamixel_workbench_controllers.h:113
DynamixelController::wheel_radius_
double wheel_radius_
Definition: dynamixel_workbench_controllers.h:89
DynamixelController::jnt_tra_msg_
trajectory_msgs::JointTrajectory * jnt_tra_msg_
Definition: dynamixel_workbench_controllers.h:92
DynamixelController::initSubscriber
void initSubscriber(void)
Definition: dynamixel_workbench_controllers.cpp:322
DynamixelController::write_period_
double write_period_
Definition: dynamixel_workbench_controllers.h:95
DynamixelController::joint_state_msg_
sensor_msgs::JointState joint_state_msg_
Definition: dynamixel_workbench_controllers.h:81
DynamixelController::initSDKHandlers
bool initSDKHandlers(void)
Definition: dynamixel_workbench_controllers.cpp:191
DynamixelController::dynamixel_command_server_
ros::ServiceServer dynamixel_command_server_
Definition: dynamixel_workbench_controllers.h:70
ItemValue::item_name
std::string item_name
Definition: dynamixel_workbench_controllers.h:48
ItemValue::value
int32_t value
Definition: dynamixel_workbench_controllers.h:49
DynamixelController::control_items_
std::map< std::string, const ControlItem * > control_items_
Definition: dynamixel_workbench_controllers.h:78
ros::NodeHandle
ros::Subscriber
trajectory_generator.h
DynamixelController::dxl_wb_
DynamixelWorkbench * dxl_wb_
Definition: dynamixel_workbench_controllers.h:75


dynamixel_workbench_controllers
Author(s): Darby Lim , Ryan Shim
autogenerated on Wed Mar 2 2022 00:13:20