1 #include <sarafun_tree/sarafun_action_nodes/GraspAction.h>
10 fillParameter(
"/sarafun/bt_action_nodes/grasp/timeout", 30.0, timeout);
16 int main(
int argc,
char **argv) {
17 ros::init(argc, argv,
"GraspAction");
18 std::string bt_client_name, action_server_name;
20 if (!ros::param::get(
"/sarafun/bt_action_nodes/grasp/action_server_name", action_server_name))
22 ROS_ERROR(
"%s missing action server name", ros::this_node::getName().c_str());
26 if (!ros::param::get(
"/sarafun/bt_action_nodes/grasp/bt_client_name", bt_client_name))
28 ROS_ERROR(
"%s missing bt client name", ros::this_node::getName().c_str());
33 ros::this_node::getName(), action_server_name, bt_client_name);
bool fillGoal(sarafun_msgs::GraspKeyframeGoal &goal)
bool fillParameter(std::string param_name, std::string ¶m_val)