Commit 6aec5d20 authored by Víctor Silos Sánchez's avatar Víctor Silos Sánchez
Browse files

TFG

parent 3d355f8b
// Copyright (C) 2010-2011 Institut de Robotica i Informatica Industrial, CSIC-UPC.
// Author
// All rights reserved.
//
// This file is part of iri-ros-pkg
// iri-ros-pkg is free software: you can redistribute it and/or modify
// it under the terms of the GNU Lesser General Public License as published by
// the Free Software Foundation, either version 3 of the License, or
// at your option) any later version.
//
// This program is distributed in the hope that it will be useful,
// but WITHOUT ANY WARRANTY; without even the implied warranty of
// MERCHANTABILITY or FITNESS FOR A PARTICULAR PURPOSE. See the
// GNU Lesser General Public License for more details.
//
// You should have received a copy of the GNU Lesser General Public License
// along with this program. If not, see <http://www.gnu.org/licenses/>.
//
// IMPORTANT NOTE: This code has been generated through a script from the
// iri_ros_scripts. Please do NOT delete any comments to guarantee the correctness
// of the scripts. ROS topics can be easly add by using those scripts. Please
// refer to the IRI wiki page for more information:
// http://wikiri.upc.es/index.php/Robotics_Lab
#ifndef _foot_alg_node_h_
#define _foot_alg_node_h_
#include <iri_base_algorithm/iri_base_algorithm.h>
#include "foot_alg.h"
#include <tf/transform_listener.h>
#include <tf/transform_broadcaster.h>
#include <string>
// [publisher subscriber headers]
#include <geometry_msgs/PoseStamped.h>
#include <std_msgs/String.h>
#include <std_msgs/Float64.h>
// [service client headers]
// [action server client headers]
/**
* \brief IRI ROS Specific Algorithm Class
*
*/
class FootAlgNode : public algorithm_base::IriBaseAlgorithm<FootAlgorithm>
{
private:
tf::TransformListener listener;
//tf::TransformBroadcaster broadcaster;
//tf::StampedTransform transformrobnothing;
tf::StampedTransform transformrobrightfoot;
tf::StampedTransform transformrobleftfoot;
tf::Vector3 goalleft;
tf::Vector3 goalright;
//tf::Vector3 goalnothing;
std::string state;
// [publisher attributes]
ros::Publisher pose_surface_publisher_;
geometry_msgs::PoseStamped pose_surface_PoseStamped_msg_;
// [subscriber attributes]
ros::Subscriber feetextended_subscriber_;
void feetextended_callback(const std_msgs::String::ConstPtr& msg);
pthread_mutex_t feetextended_mutex_;
void feetextended_mutex_enter(void);
void feetextended_mutex_exit(void);
// [service attributes]
// [client attributes]
// [action server attributes]
// [action client attributes]
/**
* \brief config variable
*
* This variable has all the driver parameters defined in the cfg config file.
* Is updated everytime function config_update() is called.
*/
Config config_;
public:
/**
* \brief Constructor
*
* This constructor initializes specific class attributes and all ROS
* communications variables to enable message exchange.
*/
FootAlgNode(void);
/**
* \brief Destructor
*
* This destructor frees all necessary dynamic memory allocated within this
* this class.
*/
~FootAlgNode(void);
protected:
/**
* \brief main node thread
*
* This is the main thread node function. Code written here will be executed
* in every node loop while the algorithm is on running state. Loop frequency
* can be tuned by modifying loop_rate attribute.
*
* Here data related to the process loop or to ROS topics (mainly data structs
* related to the MSG and SRV files) must be updated. ROS publisher objects
* must publish their data in this process. ROS client servers may also
* request data to the corresponding server topics.
*/
void mainNodeThread(void);
/**
* \brief dynamic reconfigure server callback
*
* This method is called whenever a new configuration is received through
* the dynamic reconfigure. The derivated generic algorithm class must
* implement it.
*
* \param config an object with new configuration from all algorithm
* parameters defined in the config file.
* \param level integer referring the level in which the configuration
* has been changed.
*/
void node_config_update(Config &config, uint32_t level);
/**
* \brief node add diagnostics
*
* In this abstract function additional ROS diagnostics applied to the
* specific algorithms may be added.
*/
void addNodeDiagnostics(void);
// [diagnostic functions]
// [test functions]
};
#endif
<launch>
<node pkg="tf" type="static_transform_publisher" name="tfcameratorobot" args="1.21 -0.22 1.36 0 3.14159265359 -1.57079632679 /brix_2_camera_frame world 100" />
<remap from="/iri_foot/feetextended" to="/iri_foot_extended/feetextended"/>
<node pkg="iri_foot" type ="iri_foot" name="iri_foot"/>
<node pkg="iri_foot_extended" type ="iri_foot_extended" name="iri_foot_extended"/>
</launch>
<launch>
<node pkg="tf" type="static_transform_publisher" name="tfcameratorobot" args="1.21 -0.22 1.36 0 3.14159265359 -1.57079632679 /brix_2_camera_frame world 100" />
<remap from="/iri_foot/feetextended" to="/iri_foot_extended/feetextended"/>
<node pkg="iri_foot" type ="iri_foot" name="iri_foot"/>
<node pkg="iri_foot_extended" type ="iri_foot_extended" name="iri_foot_extended"/>
</launch>
#include "foot_alg_node.h"
using namespace std;
#include <string>
FootAlgNode::FootAlgNode(void) :
algorithm_base::IriBaseAlgorithm<FootAlgorithm>()
{
//init class attributes if necessary
//this->loop_rate_ = 50;//in [Hz]
state == "Nothing";
// [init publishers]
this->pose_surface_publisher_ = this->public_node_handle_.advertise<geometry_msgs::PoseStamped>("pose_surface", 10);
// [init subscribers]
this->feetextended_subscriber_ = this->public_node_handle_.subscribe("feetextended", 10, &FootAlgNode::feetextended_callback, this);
pthread_mutex_init(&this->feetextended_mutex_,NULL);
// [init services]
// [init clients]
// [init action servers]
// [init action clients]
}
FootAlgNode::~FootAlgNode(void)
{
// [free dynamic memory]
pthread_mutex_destroy(&this->feetextended_mutex_);
}
void FootAlgNode::mainNodeThread(void)
{
// [fill msg structures]
// Initialize the topic message structure
/*
if (state == "Left")
{
ROS_INFO("Sending the position of the Left Foot!");
}
else if (state == "Right")
{
ROS_INFO("Sending the position of the Right Foot!");
}
else if (state == "Nothing")
{
//Just in case
}
*/
// Initialize the topic message structure
// Initialize the topic message structure
// [fill srv structure and make request to the server]
// [fill action structure and make request to the action server]
// [publish messages]
// Uncomment the following line to publish the topic message
// Uncomment the following line to publish the topic message
// Uncomment the following line to publish the topic message
}
/* [subscriber callbacks] */
void FootAlgNode::feetextended_callback(const std_msgs::String::ConstPtr& msg)
{
ROS_INFO("FootAlgNode::feetextended_callback: New Message Received");
string child_rightfoot("/brix_2/user_1/right_foot");
string child_leftfoot("/brix_2/user_1/left_foot");
//string child_nothing("/brix_2/user_1/nothing");
string parent_cameraframe("/brix_2_camera_frame");
string child_robot("iri_wam_link_base");
try{
ros::Time zero = ros::Time(0);
ros::Time now = ros::Time::now();
ros::Duration three_seconds = ros::Duration(3.0);
listener.waitForTransform(child_robot, child_rightfoot, zero, three_seconds);
listener.waitForTransform(child_robot, child_leftfoot, zero, three_seconds);
listener.lookupTransform(child_robot, child_rightfoot, zero,transformrobrightfoot);
listener.lookupTransform(child_robot, child_leftfoot, zero,transformrobleftfoot);
//transformrobnothing.setOrigin(tf::Vector3(0.2, 0.2, 0.2));
//transformrobnothing.setRotation(tf::Quaternion(0, 0, 0, 1));
//broadcaster.sendTransform(tf::StampedTransform(transformrobnothing, now, child_robot, child_nothing));
goalright = transformrobrightfoot.getOrigin();
goalleft = transformrobleftfoot.getOrigin();
//goalnothing = transformrobnothing.getOrigin();
}
catch (tf::TransformException &ex)
{
ROS_ERROR("%s",ex.what());
ros::Duration(1.0).sleep();
}
//use appropiate mutex to shared variables if necessary
this->alg_.lock();
this->feetextended_mutex_enter();
std::cout << msg->data << std::endl;
//unlock previously blocked shared variables
this->alg_.unlock();
this->feetextended_mutex_exit();
if (msg->data == "Right foot extended")
{
this->pose_surface_PoseStamped_msg_.pose.position.x = goalright.getX();
this->pose_surface_PoseStamped_msg_.pose.position.y = goalright.getY();
this->pose_surface_PoseStamped_msg_.pose.position.z = goalright.getZ();
this->pose_surface_PoseStamped_msg_.pose.orientation.x = 0;
this->pose_surface_PoseStamped_msg_.pose.orientation.y = 1;
this->pose_surface_PoseStamped_msg_.pose.orientation.z = 0;
this->pose_surface_PoseStamped_msg_.pose.orientation.w = 0;
this->pose_surface_PoseStamped_msg_.header.stamp = ros::Time(0);
this->pose_surface_PoseStamped_msg_.header.frame_id = "iri_wam_link_base";
this->pose_surface_publisher_.publish(this->pose_surface_PoseStamped_msg_);
//The robot has to go to the right foot
state = "Right";
ROS_INFO("Following %s Foot!",state.c_str());
}
else if (msg->data == "Left foot extended")
{
this->pose_surface_PoseStamped_msg_.pose.position.x = goalleft.getX();
this->pose_surface_PoseStamped_msg_.pose.position.y = goalleft.getY();
this->pose_surface_PoseStamped_msg_.pose.position.z = goalleft.getZ();
this->pose_surface_PoseStamped_msg_.pose.orientation.x = 0;
this->pose_surface_PoseStamped_msg_.pose.orientation.y = 1;
this->pose_surface_PoseStamped_msg_.pose.orientation.z = 0;
this->pose_surface_PoseStamped_msg_.pose.orientation.w = 0;
this->pose_surface_PoseStamped_msg_.header.stamp = ros::Time(0);
this->pose_surface_PoseStamped_msg_.header.frame_id = "iri_wam_link_base";
this->pose_surface_publisher_.publish(this->pose_surface_PoseStamped_msg_);
//The robot has to go to the left foot
state = "Left";
ROS_INFO("Following %s Foot!",state.c_str());
}
else
{
//The robot has to turn back to the initial position
state = "Nothing";
ROS_INFO("Doing %s!",state.c_str());
}
}
void FootAlgNode::feetextended_mutex_enter(void)
{
pthread_mutex_lock(&this->feetextended_mutex_);
}
void FootAlgNode::feetextended_mutex_exit(void)
{
pthread_mutex_unlock(&this->feetextended_mutex_);
}
/* [service callbacks] */
/* [action callbacks] */
/* [action requests] */
void FootAlgNode::node_config_update(Config &config, uint32_t level)
{
this->alg_.lock();
this->config_=config;
this->alg_.unlock();
}
void FootAlgNode::addNodeDiagnostics(void)
{
}
/* main function */
int main(int argc,char *argv[])
{
return algorithm_base::main<FootAlgNode>(argc, argv, "foot_alg_node");
}
#include "foot_alg_node.h"
using namespace std;
#include <string>
FootAlgNode::FootAlgNode(void) :
algorithm_base::IriBaseAlgorithm<FootAlgorithm>()
{
//init class attributes if necessary
//this->loop_rate_ = 50;//in [Hz]
state == "Nothing";
// [init publishers]
this->pose_surface_publisher_ = this->public_node_handle_.advertise<geometry_msgs::PoseStamped>("pose_surface", 10);
// [init subscribers]
this->feetextended_subscriber_ = this->public_node_handle_.subscribe("feetextended", 10, &FootAlgNode::feetextended_callback, this);
pthread_mutex_init(&this->feetextended_mutex_,NULL);
// [init services]
// [init clients]
// [init action servers]
// [init action clients]
}
FootAlgNode::~FootAlgNode(void)
{
// [free dynamic memory]
pthread_mutex_destroy(&this->feetextended_mutex_);
}
void FootAlgNode::mainNodeThread(void)
{
// [fill msg structures]
// Initialize the topic message structure
/*
if (state == "Left")
{
ROS_INFO("Sending the position of the Left Foot!");
}
else if (state == "Right")
{
ROS_INFO("Sending the position of the Right Foot!");
}
else if (state == "Nothing")
{
//Just in case
}
*/
// Initialize the topic message structure
// Initialize the topic message structure
// [fill srv structure and make request to the server]
// [fill action structure and make request to the action server]
// [publish messages]
// Uncomment the following line to publish the topic message
// Uncomment the following line to publish the topic message
// Uncomment the following line to publish the topic message
}
/* [subscriber callbacks] */
void FootAlgNode::feetextended_callback(const std_msgs::String::ConstPtr& msg)
{
ROS_INFO("FootAlgNode::feetextended_callback: New Message Received");
string child_rightfoot("/brix_2/user_1/right_foot");
string child_leftfoot("/brix_2/user_1/left_foot");
//string child_nothing("/brix_2/user_1/nothing");
string parent_cameraframe("/brix_2_camera_frame");
string child_robot("iri_wam_link_base");
try{
ros::Time zero = ros::Time(0);
ros::Time now = ros::Time::now();
ros::Duration three_seconds = ros::Duration(3.0);
listener.waitForTransform(child_robot, child_rightfoot, zero, three_seconds);
listener.waitForTransform(child_robot, child_leftfoot, zero, three_seconds);
listener.lookupTransform(child_robot, child_rightfoot, zero,transformrobrightfoot);
listener.lookupTransform(child_robot, child_leftfoot, zero,transformrobleftfoot);
//transformrobnothing.setOrigin(tf::Vector3(0.2, 0.2, 0.2));
//transformrobnothing.setRotation(tf::Quaternion(0, 0, 0, 1));
//broadcaster.sendTransform(tf::StampedTransform(transformrobnothing, now, child_robot, child_nothing));
goalright = transformrobrightfoot.getOrigin();
goalleft = transformrobleftfoot.getOrigin();
//goalnothing = transformrobnothing.getOrigin();
}
catch (tf::TransformException &ex)
{
ROS_ERROR("%s",ex.what());
ros::Duration(1.0).sleep();
}
//use appropiate mutex to shared variables if necessary
this->alg_.lock();
this->feetextended_mutex_enter();
std::cout << msg->data << std::endl;
//unlock previously blocked shared variables
this->alg_.unlock();
this->feetextended_mutex_exit();
if (msg->data == "Right foot extended")
{
this->pose_surface_PoseStamped_msg_.pose.position.x = goalright.getX();
this->pose_surface_PoseStamped_msg_.pose.position.y = goalright.getY();
this->pose_surface_PoseStamped_msg_.pose.position.z = goalright.getZ();
this->pose_surface_PoseStamped_msg_.pose.orientation.x = 0;
this->pose_surface_PoseStamped_msg_.pose.orientation.y = 1;
this->pose_surface_PoseStamped_msg_.pose.orientation.z = 0;
this->pose_surface_PoseStamped_msg_.pose.orientation.w = 0;
this->pose_surface_PoseStamped_msg_.header.stamp = ros::Time(0);
this->pose_surface_PoseStamped_msg_.header.frame_id = "iri_wam_link_base";
this->pose_surface_publisher_.publish(this->pose_surface_PoseStamped_msg_);
//The robot has to go to the right foot
state = "Right";
ROS_INFO("Following %s Foot!",state.c_str());
}
else if (msg->data == "Left foot extended")
{
this->pose_surface_PoseStamped_msg_.pose.position.x = goalleft.getX();
this->pose_surface_PoseStamped_msg_.pose.position.y = goalleft.getY();
this->pose_surface_PoseStamped_msg_.pose.position.z = goalleft.getZ();
this->pose_surface_PoseStamped_msg_.pose.orientation.x = 0;
this->pose_surface_PoseStamped_msg_.pose.orientation.y = 1;
this->pose_surface_PoseStamped_msg_.pose.orientation.z = 0;
this->pose_surface_PoseStamped_msg_.pose.orientation.w = 0;
this->pose_surface_PoseStamped_msg_.header.stamp = ros::Time(0);
this->pose_surface_PoseStamped_msg_.header.frame_id = "iri_wam_link_base";
this->pose_surface_publisher_.publish(this->pose_surface_PoseStamped_msg_);
//The robot has to go to the left foot
state = "Left";
ROS_INFO("Following %s Foot!",state.c_str());
}
else
{
//The robot has to turn back to the initial position
state = "Nothing";
ROS_INFO("Doing %s!",state.c_str());
}
}
void FootAlgNode::feetextended_mutex_enter(void)
{
pthread_mutex_lock(&this->feetextended_mutex_);
}
void FootAlgNode::feetextended_mutex_exit(void)
{
pthread_mutex_unlock(&this->feetextended_mutex_);
}
/* [service callbacks] */
/* [action callbacks] */
/* [action requests] */
void FootAlgNode::node_config_update(Config &config, uint32_t level)
{
this->alg_.lock();
this->config_=config;
this->alg_.unlock();
}
void FootAlgNode::addNodeDiagnostics(void)
{
}
/* main function */
int main(int argc,char *argv[])
{
return algorithm_base::main<FootAlgNode>(argc, argv, "foot_alg_node");
}
// Copyright (C) 2010-2011 Institut de Robotica i Informatica Industrial, CSIC-UPC.
// Author
// All rights reserved.
//
// This file is part of iri-ros-pkg
// iri-ros-pkg is free software: you can redistribute it and/or modify
// it under the terms of the GNU Lesser General Public License as published by
// the Free Software Foundation, either version 3 of the License, or
// at your option) any later version.
//
// This program is distributed in the hope that it will be useful,
// but WITHOUT ANY WARRANTY; without even the implied warranty of
// MERCHANTABILITY or FITNESS FOR A PARTICULAR PURPOSE. See the
// GNU Lesser General Public License for more details.
//
// You should have received a copy of the GNU Lesser General Public License
// along with this program. If not, see <http://www.gnu.org/licenses/>.
//
// IMPORTANT NOTE: This code has been generated through a script from the
// iri_ros_scripts. Please do NOT delete any comments to guarantee the correctness
// of the scripts. ROS topics can be easly add by using those scripts. Please
// refer to the IRI wiki page for more information:
// http://wikiri.upc.es/index.php/Robotics_Lab
#ifndef _foot_extended_alg_node_h_
#define _foot_extended_alg_node_h_
#include <iri_base_algorithm/iri_base_algorithm.h>
#include "foot_extended_alg.h"
#include <tf/transform_listener.h>
// [publisher subscriber headers]
#include <std_msgs/String.h>
#include <std_msgs/Float64.h>
// [service client headers]
// [action server client headers]
/**
* \brief IRI ROS Specific Algorithm Class
*
*/
class FootExtendedAlgNode : public algorithm_base::IriBaseAlgorithm<FootExtendedAlgorithm>
{
private:
tf::TransformListener listener;
tf::StampedTransform transform1;
tf::StampedTransform transform2;
tf::StampedTransform transform3;
tf::StampedTransform transform4;
tf::Vector3 rightfoot;
tf::Vector3 leftfoot;
tf::Vector3 leftknee;
tf::Vector3 rightknee;
tf::Vector3 sumalfoot;
tf::Vector3 sumarfoot;
tf::Vector3 sumalknee;
tf::Vector3 sumarknee;
// [publisher attributes]
ros::Publisher feetextended_publisher_;
std_msgs::String feetextended_String_msg_;
// [subscriber attributes]
// [service attributes]
// [client attributes]
// [action server attributes]