thormang3_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  * thormang3_manager.cpp
19  *
20  * Created on: 2016. 1. 21.
21  * Author: Zerom
22  */
23 
24 /* ROBOTIS Controller Header */
26 
27 /* Sensor Module Header */
29 
30 /* Motion Module Header */
37 
38 using namespace thormang3;
39 
40 int main(int argc, char **argv)
41 {
42  ros::init(argc, argv, "THORMANG3_Manager");
43  ros::NodeHandle nh;
44 
45  ROS_INFO("manager->init");
47 
48  /* Load ROS Parameter */
49  std::string offset_file = nh.param<std::string>("offset_file_path", "");
50  std::string robot_file = nh.param<std::string>("robot_file_path", "");
51 
52  std::string init_file = nh.param<std::string>("init_file_path", "");
53 
54  /* gazebo simulation */
55  controller->gazebo_mode_ = nh.param<bool>("gazebo", false);
56  if(controller->gazebo_mode_ == true)
57  {
58  ROS_WARN("SET TO GAZEBO MODE!");
59  std::string robot_name = nh.param<std::string>("gazebo_robot_name", "");
60  if(robot_name != "")
61  controller->gazebo_robot_name_ = robot_name;
62  }
63 
64  if(robot_file == "")
65  {
66  ROS_ERROR("NO robot file path in the ROS parameters.");
67  return -1;
68  }
69 
70  if(controller->initialize(robot_file, init_file) == false)
71  {
72  ROS_ERROR("ROBOTIS Controller Initialize Fail!");
73  return -1;
74  }
75 
76  if(offset_file != "")
77  controller->loadOffset(offset_file);
78 
79  sleep(1);
80 
81  /* Add Sensor Module */
82  controller->addSensorModule((robotis_framework::SensorModule*)FeetForceTorqueSensor::getInstance());
83 
84  /* Add Motion Module */
85  controller->addMotionModule((robotis_framework::MotionModule*)BaseModule::getInstance());
86  controller->addMotionModule((robotis_framework::MotionModule*)ActionModule::getInstance());
87  controller->addMotionModule((robotis_framework::MotionModule*)ManipulationModule::getInstance());
88  controller->addMotionModule((robotis_framework::MotionModule*)GripperModule::getInstance());
89  controller->addMotionModule((robotis_framework::MotionModule*)HeadControlModule::getInstance());
90  controller->addMotionModule((robotis_framework::MotionModule*)OnlineWalkingModule::getInstance());
91 
92  controller->startTimer();
93 
94  while(ros::ok())
95  {
96  usleep(1000*1000);
97  }
98 
99  return 0;
100 }
ROSCPP_DECL void init(int &argc, char **argv, const std::string &name, uint32_t options=0)
void addMotionModule(MotionModule *module)
#define ROS_WARN(...)
bool initialize(const std::string robot_file_path, const std::string init_file_path)
#define ROS_INFO(...)
int main(int argc, char **argv)
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()
void addSensorModule(SensorModule *module)
#define ROS_ERROR(...)


thormang3_manager
Author(s): Zerom , SCH , Kayman
autogenerated on Mon Jun 10 2019 15:38:00