31 int main(
int argc,
char **argv)
33 ros::init(argc, argv,
"Robotis_Manipulator_H_Manager");
40 std::string offset_file = nh.
param<std::string>(
"offset_table",
"");
41 std::string robot_file = nh.
param<std::string>(
"robot_file_path",
"");
43 std::string init_file = nh.
param<std::string>(
"init_file_path",
"");
49 std::string robot_name = nh.
param<std::string>(
"gazebo_robot_name",
"");
56 ROS_ERROR(
"NO robot file path in the ROS parameters.");
60 if (controller->
initialize(robot_file, init_file) ==
false)
62 ROS_ERROR(
"ROBOTIS Controller Initialize Fail!");
66 if (offset_file !=
"")
int main(int argc, char **argv)
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)
bool param(const std::string ¶m_name, T ¶m_val, const T &default_val) const
void loadOffset(const std::string path)