|
From: <mar...@us...> - 2009-05-11 17:18:36
|
Revision: 15167
http://personalrobots.svn.sourceforge.net/personalrobots/?rev=15167&view=rev
Author: mariusmuja
Date: 2009-05-11 17:18:33 +0000 (Mon, 11 May 2009)
Log Message:
-----------
Moved the outlet executive functions from outlet detection to a new package (plugs_functions).
This reduces the number of dependencies for the executive. Closing ticket #1348.
Modified Paths:
--------------
pkg/trunk/highlevel/executive_trex/executive_trex_pr2/CMakeLists.txt
pkg/trunk/highlevel/executive_trex/executive_trex_pr2/manifest.xml
pkg/trunk/highlevel/executive_trex/executive_trex_pr2/src/components.cpp
pkg/trunk/vision/outlet_detection/CMakeLists.txt
Added Paths:
-----------
pkg/trunk/highlevel/plugs/plugs_functions/
pkg/trunk/highlevel/plugs/plugs_functions/CMakeLists.txt
pkg/trunk/highlevel/plugs/plugs_functions/Makefile
pkg/trunk/highlevel/plugs/plugs_functions/include/
pkg/trunk/highlevel/plugs/plugs_functions/include/plugs_functions/
pkg/trunk/highlevel/plugs/plugs_functions/include/plugs_functions/plugs_functions.h
pkg/trunk/highlevel/plugs/plugs_functions/manifest.xml
pkg/trunk/highlevel/plugs/plugs_functions/src/
pkg/trunk/highlevel/plugs/plugs_functions/src/plugs_functions.cpp
Removed Paths:
-------------
pkg/trunk/vision/outlet_detection/include/outlet_detection/outlet_executive_functions.h
pkg/trunk/vision/outlet_detection/src/outlet_executive_functions.cpp
Modified: pkg/trunk/highlevel/executive_trex/executive_trex_pr2/CMakeLists.txt
===================================================================
--- pkg/trunk/highlevel/executive_trex/executive_trex_pr2/CMakeLists.txt 2009-05-11 17:06:04 UTC (rev 15166)
+++ pkg/trunk/highlevel/executive_trex/executive_trex_pr2/CMakeLists.txt 2009-05-11 17:18:33 UTC (rev 15167)
@@ -68,7 +68,7 @@
# trexdebug builds with a large number of run-time error checking running which is expensive
# but gives good feedback in discovering problems.
rospack_add_library(executive_trex_pr2_g ${TREX_FILES})
-target_link_libraries(executive_trex_pr2_g Utils_g TREX_g topological_graph outlet_executive_functions)
+target_link_libraries(executive_trex_pr2_g Utils_g TREX_g topological_graph plugs_functions)
rospack_add_executable(bin/trexdebug src/main.cpp)
target_link_libraries(bin/trexdebug executive_trex_pr2_g )
rospack_link_boost(bin/trexdebug thread)
@@ -81,7 +81,7 @@
# trexfast is about an order of magnitude faster than trexdebug
rospack_add_library(executive_trex_pr2_o ${TREX_FILES})
-target_link_libraries(executive_trex_pr2_o Utils_o TREX_o topological_graph outlet_executive_functions)
+target_link_libraries(executive_trex_pr2_o Utils_o TREX_o topological_graph plugs_functions)
rospack_add_executable(bin/trexfast src/main.cpp)
target_link_libraries(bin/trexfast executive_trex_pr2_o)
rospack_link_boost(bin/trexfast thread)
Modified: pkg/trunk/highlevel/executive_trex/executive_trex_pr2/manifest.xml
===================================================================
--- pkg/trunk/highlevel/executive_trex/executive_trex_pr2/manifest.xml 2009-05-11 17:06:04 UTC (rev 15166)
+++ pkg/trunk/highlevel/executive_trex/executive_trex_pr2/manifest.xml 2009-05-11 17:18:33 UTC (rev 15167)
@@ -8,7 +8,7 @@
<depend package="rosconsole"/>
<depend package="topological_map" />
<depend package="door_functions" />
- <depend package="outlet_detection" />
+ <depend package="plugs_functions" />
<depend package="robot_actions" />
<depend package="nav_robot_actions" />
<depend package="pr2_robot_actions" />
Modified: pkg/trunk/highlevel/executive_trex/executive_trex_pr2/src/components.cpp
===================================================================
--- pkg/trunk/highlevel/executive_trex/executive_trex_pr2/src/components.cpp 2009-05-11 17:06:04 UTC (rev 15166)
+++ pkg/trunk/highlevel/executive_trex/executive_trex_pr2/src/components.cpp 2009-05-11 17:18:33 UTC (rev 15167)
@@ -10,7 +10,7 @@
#include "Agent.hh"
#include "executive_trex_pr2/calc_angle_diff_constraint.h"
#include "executive_trex_pr2/calc_distance_constraint.h"
-#include <outlet_detection/outlet_executive_functions.h>
+#include "plugs_functions/plugs_functions.h"
#include "OrienteeringSolver.hh"
#include "Utilities.hh"
#include "LabelStr.hh"
@@ -91,7 +91,7 @@
return new_scope;
}
-
+
EntityId parentOf(const ConstrainedVariableId& var){
// If it has a parent, that parent should be a token
if(var->parent().isId()){
@@ -141,7 +141,7 @@
const LabelStr& propagatorName,
const ConstraintEngineId& constraintEngine,
const std::vector<ConstrainedVariableId>& variables)
- : ParamEqConstraint(name, propagatorName, constraintEngine, variables,
+ : ParamEqConstraint(name, propagatorName, constraintEngine, variables,
"frame_id:time_stamp:latch_state:frame_p1_x:frame_p1_y:frame_p1_z:frame_p2_x:frame_p2_y:frame_p2_z:height:hinge:rot_dir:door_p1_x:door_p1_y:door_p1_z:door_p2_x:door_p2_y:door_p2_z:handle_x:handle_y:handle_z:travel_dir_x:travel_dir_y:travel_dir_z")
{}
};
@@ -152,7 +152,7 @@
const LabelStr& propagatorName,
const ConstraintEngineId& constraintEngine,
const std::vector<ConstrainedVariableId>& variables)
- : ParamEqConstraint(name, propagatorName, constraintEngine, variables,
+ : ParamEqConstraint(name, propagatorName, constraintEngine, variables,
"frame_id:time_stamp:stowed:x:y:z")
{}
};
@@ -163,7 +163,7 @@
const LabelStr& propagatorName,
const ConstraintEngineId& constraintEngine,
const std::vector<ConstrainedVariableId>& variables)
- : ParamEqConstraint(name, propagatorName, constraintEngine, variables,
+ : ParamEqConstraint(name, propagatorName, constraintEngine, variables,
"frame_id:time_stamp:x:y:z")
{}
};
@@ -174,7 +174,7 @@
const LabelStr& propagatorName,
const ConstraintEngineId& constraintEngine,
const std::vector<ConstrainedVariableId>& variables)
- : ParamEqConstraint(name, propagatorName, constraintEngine, variables,
+ : ParamEqConstraint(name, propagatorName, constraintEngine, variables,
"frame_id:time_stamp:x:y:z:qx:qy:qz:qw")
{}
};
@@ -185,11 +185,11 @@
const LabelStr& propagatorName,
const ConstraintEngineId& constraintEngine,
const std::vector<ConstrainedVariableId>& variables)
- : ParamEqConstraint(name, propagatorName, constraintEngine, variables,
+ : ParamEqConstraint(name, propagatorName, constraintEngine, variables,
"frame_id:x:y:z:qx:qy:qz:qw")
{}
};
-
+
class TFGetRobotPoseConstraint: public Constraint {
public:
TFGetRobotPoseConstraint(const LabelStr& name,
@@ -209,14 +209,14 @@
checkError(_frame_id.isSingleton(), "The frame has not been specified for tf to get robot pose. See model for error." << _frame_id.toString());
condDebugMsg(!_frame_id.isSingleton(), "trex:error:tf_get_robot_pose", "Frame has not been specified" << variables[7]->toLongString());
}
-
+
private:
void handleExecute(){
debugMsg("trex:debug:propagation:tf_get_robot_pose", "BEFORE: " << toString());
tf::Stamped<tf::Pose> pose;
getPose(pose);
- debugMsg("trex:debug:propagation:tf_get_robot_pose", "Compute pose <" <<
+ debugMsg("trex:debug:propagation:tf_get_robot_pose", "Compute pose <" <<
pose.getOrigin().x() << ", " <<
pose.getOrigin().y() << ", " <<
pose.getOrigin().z() << ", " <<
@@ -235,7 +235,7 @@
debugMsg("trex:debug:propagation:tf_get_robot_pose", "AFTER: " << toString());
}
-
+
void getPose(tf::Stamped<tf::Pose>& pose){
tf::Stamped<tf::Pose> robot_pose;
robot_pose.setIdentity();
@@ -257,12 +257,12 @@
ROS_ERROR("Extrapolation Error: %s\n", ex.what());
}
}
-
+
IntervalDomain& _x, _y, _z, _qx, _qy, _qz, _qw; // Pose is the output
StringDomain& _frame_id;
const std::string _frame;
};
-
+
class AllBoundsSetConstraint: public Constraint{
public:
AllBoundsSetConstraint(const LabelStr& name,
@@ -315,7 +315,7 @@
const AbstractDomain& m_y;
ObjectDomain& m_location;
};
-
+
class RandomSelection: public Constraint{
public:
RandomSelection(const LabelStr& name,
@@ -360,28 +360,28 @@
executive_trex_pr2::MapGetNextMoveConstraint, "map_get_next_move", "Default");
REGISTER_CONSTRAINT(constraintEngine->getCESchema(),
executive_trex_pr2::MapConnectorConstraint, "map_connector", "Default");
- REGISTER_CONSTRAINT(constraintEngine->getCESchema(),
+ REGISTER_CONSTRAINT(constraintEngine->getCESchema(),
executive_trex_pr2::MapGetRegionFromPositionConstraint, "map_get_region_from_position", "Default");
- REGISTER_CONSTRAINT(constraintEngine->getCESchema(),
+ REGISTER_CONSTRAINT(constraintEngine->getCESchema(),
executive_trex_pr2::MapGetDoorwayFromPointsConstraint, "map_get_doorway_from_points", "Default");
- REGISTER_CONSTRAINT(constraintEngine->getCESchema(),
+ REGISTER_CONSTRAINT(constraintEngine->getCESchema(),
executive_trex_pr2::MapIsDoorwayConstraint, "map_is_doorway", "Default");
- REGISTER_CONSTRAINT(constraintEngine->getCESchema(),
+ REGISTER_CONSTRAINT(constraintEngine->getCESchema(),
executive_trex_pr2::MapGetDoorStateConstraint, "map_get_door_state", "Default");
- REGISTER_CONSTRAINT(constraintEngine->getCESchema(),
+ REGISTER_CONSTRAINT(constraintEngine->getCESchema(),
executive_trex_pr2::MapNotifyDoorBlockedConstraint, "map_notify_door_blocked", "Default");
- REGISTER_CONSTRAINT(constraintEngine->getCESchema(),
+ REGISTER_CONSTRAINT(constraintEngine->getCESchema(),
executive_trex_pr2::MapGetNearestOutletConstraint, "map_get_nearest_outlet", "Default");
- REGISTER_CONSTRAINT(constraintEngine->getCESchema(),
+ REGISTER_CONSTRAINT(constraintEngine->getCESchema(),
executive_trex_pr2::MapGetOutletStateConstraint, "map_get_outlet_state", "Default");
- REGISTER_CONSTRAINT(constraintEngine->getCESchema(),
+ REGISTER_CONSTRAINT(constraintEngine->getCESchema(),
executive_trex_pr2::MapNotifyOutletBlockedConstraint, "map_notify_outlet_blocked", "Default");
- REGISTER_CONSTRAINT(constraintEngine->getCESchema(),
+ REGISTER_CONSTRAINT(constraintEngine->getCESchema(),
TREX::TFGetRobotPoseConstraint, "tf_get_robot_pose", "Default");
// Register functions for calculations in the door domain
- REGISTER_CONSTRAINT(constraintEngine->getCESchema(),
+ REGISTER_CONSTRAINT(constraintEngine->getCESchema(),
executive_trex_pr2::GetRobotPoseForDoorConstraint, "door_get_robot_pose_for_door", "Default");
// Register SOLVER components for topological map.
@@ -405,11 +405,11 @@
const LabelStr& propagatorName,
const ConstraintEngineId& constraintEngine,
const std::vector<ConstrainedVariableId>& variables)
- :Constraint(name, propagatorName, constraintEngine, variables),
+ :Constraint(name, propagatorName, constraintEngine, variables),
_token(TREX::getParentToken(variables[0])){
checkError(variables.size() == 1, "Invalid signature for " << name.toString() << ". Check the constraint signature in the model.");
}
-
+
/**
* Will fire if any bounds are not singletons
*/
@@ -513,10 +513,10 @@
debugMsg("trex:debug:propagation:world_model:plugs_get_offset_pose", "AFTER: " << toString());
}
-
-
-
+
+
+
NearestLocation::NearestLocation(const LabelStr& name,
const LabelStr& propagatorName,
const ConstraintEngineId& constraintEngine,
@@ -527,7 +527,7 @@
m_location(static_cast<ObjectDomain&>(getCurrentDomain(variables[2]))){
checkError(variables.size() == 3, "Invalid Arg Count: " << variables.size());
}
-
+
/**
* Should wait till inputs are bound, then iterate over the locations and select the nearest one.
*/
@@ -538,7 +538,7 @@
debugMsg("trex:debug:propagation:world_model:nearest_location", "BEFORE: " << toString());
if(m_x.isSingleton() && m_y.isSingleton()){
- std::list<ObjectId> locations = m_location.makeObjectList();
+ std::list<ObjectId> locations = m_location.makeObjectList();
ObjectId nearestLocation = locations.front();
for(std::list<ObjectId>::const_iterator it = locations.begin(); it != locations.end(); ++it){
iterations++;
@@ -563,7 +563,7 @@
m_location.set(nearestLocation);
}
- debugMsg("trex:debug:propagation:world_model:nearest_location", "AFTER: " << toString()
+ debugMsg("trex:debug:propagation:world_model:nearest_location", "AFTER: " << toString()
<< std::endl << std::endl << "After " << iterations << " iterations, found a location within " << minDistance << " meters.");
}
@@ -584,7 +584,7 @@
initialized = true;
}
}
-
+
/**
* Randomly choose a value from the propagated domain
*/
Added: pkg/trunk/highlevel/plugs/plugs_functions/CMakeLists.txt
===================================================================
--- pkg/trunk/highlevel/plugs/plugs_functions/CMakeLists.txt (rev 0)
+++ pkg/trunk/highlevel/plugs/plugs_functions/CMakeLists.txt 2009-05-11 17:18:33 UTC (rev 15167)
@@ -0,0 +1,12 @@
+cmake_minimum_required(VERSION 2.4.6)
+
+include($ENV{ROS_ROOT}/core/rosbuild/rosbuild.cmake)
+set(ROS_BUILD_TYPE RelWithDebInfo)
+rospack(plugs_functions)
+gensrv()
+genmsg()
+
+set(EXECUTABLE_OUTPUT_PATH ${PROJECT_SOURCE_DIR}/bin)
+
+rospack_add_library(plugs_functions src/plugs_functions.cpp)
+
Added: pkg/trunk/highlevel/plugs/plugs_functions/Makefile
===================================================================
--- pkg/trunk/highlevel/plugs/plugs_functions/Makefile (rev 0)
+++ pkg/trunk/highlevel/plugs/plugs_functions/Makefile 2009-05-11 17:18:33 UTC (rev 15167)
@@ -0,0 +1 @@
+include $(shell rospack find mk)/cmake.mk
Copied: pkg/trunk/highlevel/plugs/plugs_functions/include/plugs_functions/plugs_functions.h (from rev 15166, pkg/trunk/vision/outlet_detection/include/outlet_detection/outlet_executive_functions.h)
===================================================================
--- pkg/trunk/highlevel/plugs/plugs_functions/include/plugs_functions/plugs_functions.h (rev 0)
+++ pkg/trunk/highlevel/plugs/plugs_functions/include/plugs_functions/plugs_functions.h 2009-05-11 17:18:33 UTC (rev 15167)
@@ -0,0 +1,44 @@
+/*********************************************************************
+ * Software License Agreement (BSD License)
+ *
+ * Copyright (c) 2008, Willow Garage, Inc.
+ * All rights reserved.
+ *
+ * Redistribution and use in source and binary forms, with or without
+ * modification, are permitted provided that the following conditions
+ * are met:
+ *
+ * * Redistributions of source code must retain the above copyright
+ * notice, this list of conditions and the following disclaimer.
+ * * Redistributions in binary form must reproduce the above
+ * copyright notice, this list of conditions and the following
+ * disclaimer in the documentation and/or other materials provided
+ * with the distribution.
+ * * Neither the name of Willow Garage nor the names of its
+ * contributors may be used to endorse or promote products derived
+ * from this software without specific prior written permission.
+ *
+ * THIS SOFTWARE IS PROVIDED BY THE COPYRIGHT HOLDERS AND CONTRIBUTORS
+ * "AS IS" AND ANY EXPRESS OR IMPLIED WARRANTIES, INCLUDING, BUT NOT
+ * LIMITED TO, THE IMPLIED WARRANTIES OF MERCHANTABILITY AND FITNESS
+ * FOR A PARTICULAR PURPOSE ARE DISCLAIMED. IN NO EVENT SHALL THE
+ * COPYRIGHT OWNER OR CONTRIBUTORS BE LIABLE FOR ANY DIRECT, INDIRECT,
+ * INCIDENTAL, SPECIAL, EXEMPLARY, OR CONSEQUENTIAL DAMAGES (INCLUDING,
+ * BUT NOT LIMITED TO, PROCUREMENT OF SUBSTITUTE GOODS OR SERVICES;
+ * LOSS OF USE, DATA, OR PROFITS; OR BUSINESS INTERRUPTION) HOWEVER
+ * CAUSED AND ON ANY THEORY OF LIABILITY, WHETHER IN CONTRACT, STRICT
+ * LIABILITY, OR TORT (INCLUDING NEGLIGENCE OR OTHERWISE) ARISING IN
+ * ANY WAY OUT OF THE USE OF THIS SOFTWARE, EVEN IF ADVISED OF THE
+ * POSSIBILITY OF SUCH DAMAGE.
+ *********************************************************************/
+
+#ifndef OUTLET_EXECUTIVE_FUNCTIONS_H
+#define OUTLET_EXECUTIVE_FUNCTIONS_H
+
+
+#include <robot_msgs/Pose.h>
+
+robot_msgs::Pose transformOutletPose(robot_msgs::Pose outletPose, float value);
+
+
+#endif // OUTLET_EXECUTIVE_FUNCTIONS_H
Added: pkg/trunk/highlevel/plugs/plugs_functions/manifest.xml
===================================================================
--- pkg/trunk/highlevel/plugs/plugs_functions/manifest.xml (rev 0)
+++ pkg/trunk/highlevel/plugs/plugs_functions/manifest.xml 2009-05-11 17:18:33 UTC (rev 15167)
@@ -0,0 +1,21 @@
+<package>
+ <description>
+ Plugs functions package
+ </description>
+
+ <author>Marius Muja</author>
+ <license>BSD</license>
+ <url>http://pr.willowgarage.com</url>
+ <review status="experimental" notes="beta"/>
+
+ <depend package="roscpp" />
+ <depend package="robot_msgs" />
+ <depend package="tf"/>
+
+
+ <export>
+ <cpp cflags="-I${prefix}/msg/cpp -I${prefix}/srv/cpp -I${prefix}/include" lflags="-Wl,-rpath,${prefix}/lib -L${prefix}/lib -lplugs_functions"/>
+ </export>
+
+
+</package>
Copied: pkg/trunk/highlevel/plugs/plugs_functions/src/plugs_functions.cpp (from rev 15166, pkg/trunk/vision/outlet_detection/src/outlet_executive_functions.cpp)
===================================================================
--- pkg/trunk/highlevel/plugs/plugs_functions/src/plugs_functions.cpp (rev 0)
+++ pkg/trunk/highlevel/plugs/plugs_functions/src/plugs_functions.cpp 2009-05-11 17:18:33 UTC (rev 15167)
@@ -0,0 +1,54 @@
+/*********************************************************************
+ * Software License Agreement (BSD License)
+ *
+ * Copyright (c) 2008, Willow Garage, Inc.
+ * All rights reserved.
+ *
+ * Redistribution and use in source and binary forms, with or without
+ * modification, are permitted provided that the following conditions
+ * are met:
+ *
+ * * Redistributions of source code must retain the above copyright
+ * notice, this list of conditions and the following disclaimer.
+ * * Redistributions in binary form must reproduce the above
+ * copyright notice, this list of conditions and the following
+ * disclaimer in the documentation and/or other materials provided
+ * with the distribution.
+ * * Neither the name of Willow Garage nor the names of its
+ * contributors may be used to endorse or promote products derived
+ * from this software without specific prior written permission.
+ *
+ * THIS SOFTWARE IS PROVIDED BY THE COPYRIGHT HOLDERS AND CONTRIBUTORS
+ * "AS IS" AND ANY EXPRESS OR IMPLIED WARRANTIES, INCLUDING, BUT NOT
+ * LIMITED TO, THE IMPLIED WARRANTIES OF MERCHANTABILITY AND FITNESS
+ * FOR A PARTICULAR PURPOSE ARE DISCLAIMED. IN NO EVENT SHALL THE
+ * COPYRIGHT OWNER OR CONTRIBUTORS BE LIABLE FOR ANY DIRECT, INDIRECT,
+ * INCIDENTAL, SPECIAL, EXEMPLARY, OR CONSEQUENTIAL DAMAGES (INCLUDING,
+ * BUT NOT LIMITED TO, PROCUREMENT OF SUBSTITUTE GOODS OR SERVICES;
+ * LOSS OF USE, DATA, OR PROFITS; OR BUSINESS INTERRUPTION) HOWEVER
+ * CAUSED AND ON ANY THEORY OF LIABILITY, WHETHER IN CONTRACT, STRICT
+ * LIABILITY, OR TORT (INCLUDING NEGLIGENCE OR OTHERWISE) ARISING IN
+ * ANY WAY OUT OF THE USE OF THIS SOFTWARE, EVEN IF ADVISED OF THE
+ * POSSIBILITY OF SUCH DAMAGE.
+ *********************************************************************/
+
+
+#include "plugs_functions/plugs_functions.h"
+#include <tf/tf.h>
+
+
+robot_msgs::Pose transformOutletPose(robot_msgs::Pose outletPose, float value)
+{
+ tf::Pose tf_pose;
+ robot_msgs::Pose final_pose;
+
+ tf::PoseMsgToTF(outletPose,tf_pose);
+ tf::Point point(-value,0,0);
+ tf::Point new_origin = tf_pose*point;
+
+ tf_pose.setOrigin(new_origin);
+
+ tf::PoseTFToMsg(tf_pose,final_pose);
+
+ return final_pose;
+}
Modified: pkg/trunk/vision/outlet_detection/CMakeLists.txt
===================================================================
--- pkg/trunk/vision/outlet_detection/CMakeLists.txt 2009-05-11 17:06:04 UTC (rev 15166)
+++ pkg/trunk/vision/outlet_detection/CMakeLists.txt 2009-05-11 17:18:33 UTC (rev 15167)
@@ -41,5 +41,3 @@
target_link_libraries(plug_node plug)
#rospack_add_executable(calibrate_plug src/calibrate_plug.cpp)
-
-rospack_add_library(outlet_executive_functions src/outlet_executive_functions.cpp)
Deleted: pkg/trunk/vision/outlet_detection/include/outlet_detection/outlet_executive_functions.h
===================================================================
--- pkg/trunk/vision/outlet_detection/include/outlet_detection/outlet_executive_functions.h 2009-05-11 17:06:04 UTC (rev 15166)
+++ pkg/trunk/vision/outlet_detection/include/outlet_detection/outlet_executive_functions.h 2009-05-11 17:18:33 UTC (rev 15167)
@@ -1,44 +0,0 @@
-/*********************************************************************
- * Software License Agreement (BSD License)
- *
- * Copyright (c) 2008, Willow Garage, Inc.
- * All rights reserved.
- *
- * Redistribution and use in source and binary forms, with or without
- * modification, are permitted provided that the following conditions
- * are met:
- *
- * * Redistributions of source code must retain the above copyright
- * notice, this list of conditions and the following disclaimer.
- * * Redistributions in binary form must reproduce the above
- * copyright notice, this list of conditions and the following
- * disclaimer in the documentation and/or other materials provided
- * with the distribution.
- * * Neither the name of Willow Garage nor the names of its
- * contributors may be used to endorse or promote products derived
- * from this software without specific prior written permission.
- *
- * THIS SOFTWARE IS PROVIDED BY THE COPYRIGHT HOLDERS AND CONTRIBUTORS
- * "AS IS" AND ANY EXPRESS OR IMPLIED WARRANTIES, INCLUDING, BUT NOT
- * LIMITED TO, THE IMPLIED WARRANTIES OF MERCHANTABILITY AND FITNESS
- * FOR A PARTICULAR PURPOSE ARE DISCLAIMED. IN NO EVENT SHALL THE
- * COPYRIGHT OWNER OR CONTRIBUTORS BE LIABLE FOR ANY DIRECT, INDIRECT,
- * INCIDENTAL, SPECIAL, EXEMPLARY, OR CONSEQUENTIAL DAMAGES (INCLUDING,
- * BUT NOT LIMITED TO, PROCUREMENT OF SUBSTITUTE GOODS OR SERVICES;
- * LOSS OF USE, DATA, OR PROFITS; OR BUSINESS INTERRUPTION) HOWEVER
- * CAUSED AND ON ANY THEORY OF LIABILITY, WHETHER IN CONTRACT, STRICT
- * LIABILITY, OR TORT (INCLUDING NEGLIGENCE OR OTHERWISE) ARISING IN
- * ANY WAY OUT OF THE USE OF THIS SOFTWARE, EVEN IF ADVISED OF THE
- * POSSIBILITY OF SUCH DAMAGE.
- *********************************************************************/
-
-#ifndef OUTLET_EXECUTIVE_FUNCTIONS_H
-#define OUTLET_EXECUTIVE_FUNCTIONS_H
-
-
-#include <robot_msgs/Pose.h>
-
-robot_msgs::Pose transformOutletPose(robot_msgs::Pose outletPose, float value);
-
-
-#endif // OUTLET_EXECUTIVE_FUNCTIONS_H
Deleted: pkg/trunk/vision/outlet_detection/src/outlet_executive_functions.cpp
===================================================================
--- pkg/trunk/vision/outlet_detection/src/outlet_executive_functions.cpp 2009-05-11 17:06:04 UTC (rev 15166)
+++ pkg/trunk/vision/outlet_detection/src/outlet_executive_functions.cpp 2009-05-11 17:18:33 UTC (rev 15167)
@@ -1,54 +0,0 @@
-/*********************************************************************
- * Software License Agreement (BSD License)
- *
- * Copyright (c) 2008, Willow Garage, Inc.
- * All rights reserved.
- *
- * Redistribution and use in source and binary forms, with or without
- * modification, are permitted provided that the following conditions
- * are met:
- *
- * * Redistributions of source code must retain the above copyright
- * notice, this list of conditions and the following disclaimer.
- * * Redistributions in binary form must reproduce the above
- * copyright notice, this list of conditions and the following
- * disclaimer in the documentation and/or other materials provided
- * with the distribution.
- * * Neither the name of Willow Garage nor the names of its
- * contributors may be used to endorse or promote products derived
- * from this software without specific prior written permission.
- *
- * THIS SOFTWARE IS PROVIDED BY THE COPYRIGHT HOLDERS AND CONTRIBUTORS
- * "AS IS" AND ANY EXPRESS OR IMPLIED WARRANTIES, INCLUDING, BUT NOT
- * LIMITED TO, THE IMPLIED WARRANTIES OF MERCHANTABILITY AND FITNESS
- * FOR A PARTICULAR PURPOSE ARE DISCLAIMED. IN NO EVENT SHALL THE
- * COPYRIGHT OWNER OR CONTRIBUTORS BE LIABLE FOR ANY DIRECT, INDIRECT,
- * INCIDENTAL, SPECIAL, EXEMPLARY, OR CONSEQUENTIAL DAMAGES (INCLUDING,
- * BUT NOT LIMITED TO, PROCUREMENT OF SUBSTITUTE GOODS OR SERVICES;
- * LOSS OF USE, DATA, OR PROFITS; OR BUSINESS INTERRUPTION) HOWEVER
- * CAUSED AND ON ANY THEORY OF LIABILITY, WHETHER IN CONTRACT, STRICT
- * LIABILITY, OR TORT (INCLUDING NEGLIGENCE OR OTHERWISE) ARISING IN
- * ANY WAY OUT OF THE USE OF THIS SOFTWARE, EVEN IF ADVISED OF THE
- * POSSIBILITY OF SUCH DAMAGE.
- *********************************************************************/
-
-
-#include "outlet_detection/outlet_executive_functions.h"
-#include <tf/tf.h>
-
-
-robot_msgs::Pose transformOutletPose(robot_msgs::Pose outletPose, float value)
-{
- tf::Pose tf_pose;
- robot_msgs::Pose final_pose;
-
- tf::PoseMsgToTF(outletPose,tf_pose);
- tf::Point point(-value,0,0);
- tf::Point new_origin = tf_pose*point;
-
- tf_pose.setOrigin(new_origin);
-
- tf::PoseTFToMsg(tf_pose,final_pose);
-
- return final_pose;
-}
This was sent by the SourceForge.net collaborative development platform, the world's largest Open Source development site.
|