Go to the documentation of this file.00001 #include "robotiq_action_server/robotiq_c_model_action_server.h"
00002
00003 namespace
00004 {
00005
00006 robotiq_action_server::CModelGripperParams c2_85_defaults()
00007 {
00008 robotiq_action_server::CModelGripperParams params;
00009 params.min_gap_ = -.017;
00010 params.max_gap_ = 0.085;
00011 params.min_effort_ = 40.0;
00012 params.max_effort_ = 100.0;
00013
00014 return params;
00015 }
00016 }
00017
00018 int main(int argc, char** argv)
00019 {
00020
00021 ros::init(argc, argv, "gripper_action_server");
00022
00023
00024 ros::NodeHandle private_nh("~");
00025
00026 std::string gripper_name;
00027 private_nh.param<std::string>("gripper_name", gripper_name, "gripper");
00028
00029
00030 robotiq_action_server::CModelGripperParams cparams = c2_85_defaults();
00031
00032
00033 private_nh.param<double>("min_gap", cparams.min_gap_, cparams.min_gap_);
00034 private_nh.param<double>("max_gap", cparams.max_gap_, cparams.max_gap_);
00035 private_nh.param<double>("min_effort", cparams.min_effort_, cparams.min_effort_);
00036 private_nh.param<double>("max_effort", cparams.max_effort_, cparams.max_effort_);
00037
00038 ROS_INFO("Initializing Robotiq action server for gripper: %s", gripper_name.c_str());
00039
00040
00041 robotiq_action_server::CModelGripperActionServer gripper (gripper_name, cparams);
00042
00043 ROS_INFO("Robotiq action-server spinning for gripper: %s", gripper_name.c_str());
00044 ros::spin();
00045 }