40 int main(
int argc,
char **argv)
42 ros::init(argc, argv,
"THORMANG3_Manager");
49 std::string offset_file = nh.
param<std::string>(
"offset_file_path",
"");
50 std::string robot_file = nh.
param<std::string>(
"robot_file_path",
"");
52 std::string init_file = nh.
param<std::string>(
"init_file_path",
"");
59 std::string robot_name = nh.
param<std::string>(
"gazebo_robot_name",
"");
66 ROS_ERROR(
"NO robot file path in the ROS parameters.");
70 if(controller->
initialize(robot_file, init_file) ==
false)
72 ROS_ERROR(
"ROBOTIS Controller Initialize Fail!");
std::string gazebo_robot_name_
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)
int main(int argc, char **argv)
bool param(const std::string ¶m_name, T ¶m_val, const T &default_val) const
void loadOffset(const std::string path)
void addSensorModule(SensorModule *module)