joint_operator.h
Go to the documentation of this file.
1 /*******************************************************************************
2 * Copyright 2016 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_OPERATORS_H
20 #define DYNAMIXEL_WORKBENCH_OPERATORS_H
21 
22 #include <ros/ros.h>
23 #include <yaml-cpp/yaml.h>
24 
25 #include <trajectory_msgs/JointTrajectory.h>
26 #include <trajectory_msgs/JointTrajectoryPoint.h>
27 
28 #include <std_srvs/Trigger.h>
29 
31 {
32  private:
33  // ROS NodeHandle
36 
37  // ROS Parameters
38 
39  // ROS Topic Publisher
41 
42  // ROS Topic Subscriber
43 
44  // ROS Service Server
46 
47  // ROS Service Client
48 
49  trajectory_msgs::JointTrajectory *jnt_tra_msg_;
50  bool is_loop_;
51 
52  public:
53  JointOperator();
55 
56  bool isLoop(void){ return is_loop_;}
57 
58  bool getTrajectoryInfo(const std::string yaml_file, trajectory_msgs::JointTrajectory *jnt_tra_msg);
59  bool moveCommandMsgCallback(std_srvs::Trigger::Request &req,
60  std_srvs::Trigger::Response &res);
61 };
62 
63 #endif // DYNAMIXEL_WORKBENCH_OPERATORS_H
JointOperator::is_loop_
bool is_loop_
Definition: joint_operator.h:64
JointOperator::node_handle_
ros::NodeHandle node_handle_
Definition: joint_operator.h:48
JointOperator::JointOperator
JointOperator()
Definition: joint_operator.cpp:21
JointOperator::isLoop
bool isLoop(void)
Definition: joint_operator.h:70
ros::Publisher
JointOperator::getTrajectoryInfo
bool getTrajectoryInfo(const std::string yaml_file, trajectory_msgs::JointTrajectory *jnt_tra_msg)
Definition: joint_operator.cpp:46
JointOperator::joint_trajectory_pub_
ros::Publisher joint_trajectory_pub_
Definition: joint_operator.h:54
ros.h
JointOperator::priv_node_handle_
ros::NodeHandle priv_node_handle_
Definition: joint_operator.h:49
JointOperator::jnt_tra_msg_
trajectory_msgs::JointTrajectory * jnt_tra_msg_
Definition: joint_operator.h:63
JointOperator
Definition: joint_operator.h:30
ros::ServiceServer
JointOperator::~JointOperator
~JointOperator()
Definition: joint_operator.cpp:42
JointOperator::move_command_server_
ros::ServiceServer move_command_server_
Definition: joint_operator.h:59
JointOperator::moveCommandMsgCallback
bool moveCommandMsgCallback(std_srvs::Trigger::Request &req, std_srvs::Trigger::Response &res)
Definition: joint_operator.cpp:101
ros::NodeHandle


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