Skip to content
Snippets Groups Projects
Commit e90b0e7f authored by Johannes Mey's avatar Johannes Mey
Browse files

remove use of parameter

parent 5e1af023
Branches
No related tags found
No related merge requests found
...@@ -27,10 +27,6 @@ void collect(ros::NodeHandle node_handle, geometry_msgs::TransformStamped t) { ...@@ -27,10 +27,6 @@ void collect(ros::NodeHandle node_handle, geometry_msgs::TransformStamped t) {
} }
} }
void collectPose(ros::NodeHandle &node_handle){
node_handle.setParam("collect_pose", true);
}
void cleanUp(ros::NodeHandle &node_handle) { void cleanUp(ros::NodeHandle &node_handle) {
ros::ServiceClient client = node_handle.serviceClient<panda_teaching::DeletePose>("DeleteCollectedPoses"); ros::ServiceClient client = node_handle.serviceClient<panda_teaching::DeletePose>("DeleteCollectedPoses");
panda_teaching::DeletePose srv; panda_teaching::DeletePose srv;
...@@ -40,13 +36,25 @@ void cleanUp(ros::NodeHandle &node_handle){ ...@@ -40,13 +36,25 @@ void cleanUp(ros::NodeHandle &node_handle){
} }
} }
// global variable. should be put in class
tf2_ros::Buffer tfBuffer;
void collectorCallback(const std_msgs::String::ConstPtr &msg, ros::NodeHandle &node_handle) { void collectorCallback(const std_msgs::String::ConstPtr &msg, ros::NodeHandle &node_handle) {
ROS_INFO("Retrieved new pose-message..."); ROS_INFO("Retrieved new pose-message...");
if (msg->data.compare("collect") == 0) { if (msg->data.compare("collect") == 0) {
ROS_INFO("Collecting new pose for gripper..."); ROS_INFO("Collecting new pose for gripper...");
collectPose(node_handle); try {
geometry_msgs::TransformStamped transformStamped = tfBuffer.lookupTransform("world", "panda_hand", ros::Time(0));
std::cout << "Collected pose: " << transformStamped << std::endl;
collect(node_handle, transformStamped);
}
catch (tf2::TransformException &ex) {
ROS_ERROR_STREAM("transform_error: " << ex.what() << std::endl);
ros::Duration(1.0).sleep();
}
return; return;
} }
...@@ -62,38 +70,12 @@ int main(int argc, char **argv) { ...@@ -62,38 +70,12 @@ int main(int argc, char **argv) {
ros::NodeHandle node_handle; ros::NodeHandle node_handle;
ros::Subscriber sub = node_handle.subscribe<std_msgs::String>("collectPose", 1000, boost::bind(&collectorCallback, _1, boost::ref(node_handle))); ros::Subscriber sub = node_handle.subscribe<std_msgs::String>("collectPose", 1000, boost::bind(&collectorCallback, _1, boost::ref(node_handle)));
tf2_ros::Buffer tfBuffer;
tf2_ros::TransformListener tfListener(tfBuffer); tf2_ros::TransformListener tfListener(tfBuffer);
ros::Rate rate(10.0); ros::Rate rate(10.0);
while (node_handle.ok()) { ros::spin();
geometry_msgs::TransformStamped transformStamped;
try {
// world == (0, 0, 0, 0)
transformStamped = tfBuffer.lookupTransform("world", "panda_hand",
ros::Time(0));
bool collect_pose = false;
node_handle.getParam("collect_pose", collect_pose);
if (collect_pose) {
std::cout << "Collected pose: " << transformStamped << std::endl;
node_handle.setParam("collect_pose", false);
collect(node_handle, transformStamped);
}
}
catch (tf2::TransformException &ex) {
std::cout << "transform_error: " << ex.what() << std::endl;
ros::Duration(1.0).sleep();
continue;
}
ros::spinOnce();
}
return 0; return 0;
}; };
0% Loading or .
You are about to add 0 people to the discussion. Proceed with caution.
Please register or to comment