ValidateTcpPose.cpp
Go to the documentation of this file.
1/*
2 * This file is part of ArmarX.
3 *
4 * Copyright (C) 2014-2016, High Performance Humanoid Technologies (H2T), Karlsruhe Institute of Technology (KIT), all rights reserved.
5 *
6 * ArmarX is free software; you can redistribute it and/or modify
7 * it under the terms of the GNU General Public License version 2 as
8 * published by the Free Software Foundation.
9 *
10 * ArmarX is distributed in the hope that it will be useful, but
11 * WITHOUT ANY WARRANTY; without even the implied warranty of
12 * MERCHANTABILITY or FITNESS FOR A PARTICULAR PURPOSE. See the
13 * GNU General Public License for more details.
14 *
15 * You should have received a copy of the GNU General Public License
16 * along with this program. If not, see <http://www.gnu.org/licenses/>.
17 *
18 * @package RobotSkillTemplates::FindAndGraspObjectGroup
19 * @author Valerij Wittenbeck ( valerij dot wittenbeck at student dot kit dot edu )
20 * @date 2014
21 * @copyright http://www.gnu.org/licenses/gpl-2.0.txt
22 * GNU General Public License
23 */
24
25#include "ValidateTcpPose.h"
26
27#include <VirtualRobot/LinkedCoordinate.h>
28
30
31using namespace armarx;
32using namespace FindAndGraspObjectGroup;
33
34// DO NOT EDIT NEXT LINE
35ValidateTcpPose::SubClassRegistry ValidateTcpPose::Registry(ValidateTcpPose::GetName(),
37
42
43void
45{
46 using namespace Eigen;
47
50 new RemoteRobot(context->robotStateComponent->getRobotSnapshot("ValidateTCPPoseTime")));
51 VirtualRobot::LinkedCoordinate actualPose(robot);
52 actualPose.set(
53 robot->getRobotNodeSet(getInput<std::string>("kinematicChainName"))->getTCP()->getName(),
54 Vector3f(0, 0, 0));
55 actualPose.changeFrame(robot->getRootNode());
56 Vector3f actualPosition = actualPose.getPosition();
57 Quaternionf actualOrientation(actualPose.getPose().block<3, 3>(0, 0));
58
59
60 VirtualRobot::LinkedCoordinate targetPose =
62 getInput<FramedPosition>("targetTCPPosition"),
63 getInput<FramedOrientation>("targetTCPOrientation"));
64 targetPose.changeFrame(robot->getRootNode());
65 Vector3f targetPosition = targetPose.getPosition();
66 Quaternionf targetOrientation(targetPose.getPose().block<3, 3>(0, 0));
67
68 float cartesianDistance =
69 sqrtf(((targetPosition - actualPosition).dot(targetPosition - actualPosition)));
70 float orientationDistance = actualOrientation.angularDistance(targetOrientation);
71
72 setOutput("TCPDistanceToTarget", cartesianDistance);
73 setOutput("TCPOrientationDistanceToTarget", orientationDistance);
74 bool withOri = getInput<bool>("ikWithOrientation");
75
76 if (cartesianDistance <= getInput<float>("targetPositionDistanceTolerance") &&
77 (!withOri || orientationDistance <= getInput<float>("targetOrientationDistanceTolerance")))
78 {
80 }
81 else
82 {
84 << "Target pose has not been reached with the desired accuracy. Cartesian distance: "
85 << cartesianDistance << ", orientation distance: " << orientationDistance << " ";
86 ARMARX_INFO << "Actual pose: " << actualPose.getPose();
87 ARMARX_INFO << "Target pose: " << targetPose.getPose();
89 }
90
91 ARMARX_VERBOSE << "Done ValidateTcpPose::onEnter()";
92}
93
94// DO NOT EDIT NEXT FUNCTION
95std::string
97{
98 return "ValidateTcpPose";
99}
100
101// DO NOT EDIT NEXT FUNCTION
ValidateTcpPose(XMLStateConstructorParams stateData)
void onEnter() override
Virtual function, in which the behaviour of state is defined, when it is entered. Can be overridden,...
static XMLStateFactoryBasePtr CreateInstance(XMLStateConstructorParams stateData)
static VirtualRobot::LinkedCoordinate createLinkedCoordinate(const VirtualRobot::RobotPtr &virtualRobot, const FramedPositionPtr &position, const FramedOrientationPtr &orientation)
Mimics the behaviour of the VirtualRobot::Robot class while redirecting everything to an Ice proxy.
RobotStateComponentInterfacePrx robotStateComponent
Prx for the RobotState.
ContextType * getContext() const
Definition StateBase.h:71
void sendEvent(const EventPtr event, StateBasePtr eventProcessor=nullptr)
Function to send an event to a specific state from an onEnter()-function. Must not be called anywhere...
Definition StateUtil.cpp:40
void setOutput(std::string const &key, const Variant &value)
setOuput() sets an output parameter of this state.
Definition State.cpp:482
std::enable_if_t< std::is_base_of_v< VariantDataClass, T >, IceInternal::Handle< T > > getInput(const std::string &key) const
getInput can be used to access a specific input parameter.
Definition State.h:620
XMLStateTemplate(const XMLStateConstructorParams &params)
Definition XMLState.h:149
#define ARMARX_INFO
The normal logging level.
Definition Logging.h:181
#define ARMARX_WARNING
The logging level for unexpected behaviour, but not a serious problem.
Definition Logging.h:193
#define ARMARX_VERBOSE
The logging level for verbose information.
Definition Logging.h:187
Quaternion< float, 0 > Quaternionf
std::shared_ptr< class Robot > RobotPtr
Definition Bus.h:19
This file offers overloads of toIce() and fromIce() functions for STL container types.
IceInternal::Handle< XMLStateFactoryBase > XMLStateFactoryBasePtr
Definition XMLState.h:64
double dot(const Point &x, const Point &y)
Definition point.hpp:57