manipulator_h_manager.cpp
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 /*
18  * RobotisManager.cpp
19  *
20  * Created on: 2016. 1. 21.
21  * Author: Zerom
22  */
23 
26 
27 /* Motion Module Header */
28 
29 using namespace robotis_manipulator_h;
30 
31 int main(int argc, char **argv)
32 {
33  ros::init(argc, argv, "Robotis_Manipulator_H_Manager");
34  ros::NodeHandle nh;
35 
36  ROS_INFO("manager->init");
38 
39  /* Load ROS Parameter */
40  std::string offset_file = nh.param<std::string>("offset_table", "");
41  std::string robot_file = nh.param<std::string>("robot_file_path", "");
42 
43  std::string init_file = nh.param<std::string>("init_file_path", "");
44 
45  /* gazebo simulation */
46  controller->gazebo_mode_ = nh.param<bool>("gazebo", false);
47  if (controller->gazebo_mode_ == true)
48  {
49  std::string robot_name = nh.param<std::string>("gazebo_robot_name", "");
50  if (robot_name != "")
51  controller->gazebo_robot_name_ = robot_name;
52  }
53 
54  if (robot_file == "")
55  {
56  ROS_ERROR("NO robot file path in the ROS parameters.");
57  return -1;
58  }
59 
60  if (controller->initialize(robot_file, init_file) == false)
61  {
62  ROS_ERROR("ROBOTIS Controller Initialize Fail!");
63  return -1;
64  }
65 
66  if (offset_file != "")
67  controller->loadOffset(offset_file);
68 
69  sleep(1);
70 
71  /* Add Motion Module */
72  controller->addMotionModule((robotis_framework::MotionModule*) BaseModule::getInstance());
73 
74  controller->startTimer();
75 
76  while (ros::ok())
77  {
78  usleep(100);
79  }
80 
81  return 0;
82 }
int main(int argc, char **argv)
ROSCPP_DECL void init(int &argc, char **argv, const std::string &name, uint32_t options=0)
void addMotionModule(MotionModule *module)
bool initialize(const std::string robot_file_path, const std::string init_file_path)
#define ROS_INFO(...)
bool param(const std::string &param_name, T &param_val, const T &default_val) const
void loadOffset(const std::string path)
ROSCPP_DECL bool ok()
#define ROS_ERROR(...)


manipulator_h_manager
Author(s): SCH
autogenerated on Mon Jun 10 2019 14:03:00