point_to_plane.cpp
Go to the documentation of this file.
1 //
2 // Copyright (c) 2018-2020, Wolfgang Merkt, University of Oxford
3 // All rights reserved.
4 //
5 // Redistribution and use in source and binary forms, with or without
6 // modification, are permitted provided that the following conditions are met:
7 //
8 // * Redistributions of source code must retain the above copyright notice,
9 // this list of conditions and the following disclaimer.
10 // * Redistributions in binary form must reproduce the above copyright
11 // notice, this list of conditions and the following disclaimer in the
12 // documentation and/or other materials provided with the distribution.
13 // * Neither the name of nor the names of its contributors may be used to
14 // endorse or promote products derived from this software without specific
15 // prior written permission.
16 //
17 // THIS SOFTWARE IS PROVIDED BY THE COPYRIGHT HOLDERS AND CONTRIBUTORS "AS IS"
18 // AND ANY EXPRESS OR IMPLIED WARRANTIES, INCLUDING, BUT NOT LIMITED TO, THE
19 // IMPLIED WARRANTIES OF MERCHANTABILITY AND FITNESS FOR A PARTICULAR PURPOSE
20 // ARE DISCLAIMED. IN NO EVENT SHALL THE COPYRIGHT OWNER OR CONTRIBUTORS BE
21 // LIABLE FOR ANY DIRECT, INDIRECT, INCIDENTAL, SPECIAL, EXEMPLARY, OR
22 // CONSEQUENTIAL DAMAGES (INCLUDING, BUT NOT LIMITED TO, PROCUREMENT OF
23 // SUBSTITUTE GOODS OR SERVICES; LOSS OF USE, DATA, OR PROFITS; OR BUSINESS
24 // INTERRUPTION) HOWEVER CAUSED AND ON ANY THEORY OF LIABILITY, WHETHER IN
25 // CONTRACT, STRICT LIABILITY, OR TORT (INCLUDING NEGLIGENCE OR OTHERWISE)
26 // ARISING IN ANY WAY OUT OF THE USE OF THIS SOFTWARE, EVEN IF ADVISED OF THE
27 // POSSIBILITY OF SUCH DAMAGE.
28 //
29 
30 #include <exotica_core/server.h>
33 
35 
36 namespace exotica
37 {
38 void PointToPlane::Instantiate(const PointToPlaneInitializer& init)
39 {
40  if (debug_ && Server::IsRos())
41  {
42  debug_pub_ = Server::Advertise<visualization_msgs::MarkerArray>(object_name_ + "/planes", 1, true);
43  }
44 }
45 
47 {
48  if (phi.rows() != kinematics[0].Phi.rows()) ThrowNamed("Wrong size of phi!");
49 
50  for (int i = 0; i < kinematics[0].Phi.rows(); ++i)
51  {
52  phi(i) = kinematics[0].Phi(i).p.data[2];
53  }
54 
55  if (debug_ && Server::IsRos()) PublishDebug();
56 }
57 
59 {
60  if (phi.rows() != kinematics[0].Phi.rows()) ThrowNamed("Wrong size of phi!");
61  if (jacobian.rows() != kinematics[0].jacobian.rows() || jacobian.cols() != kinematics[0].jacobian(0).data.cols()) ThrowNamed("Wrong size of jacobian! " << kinematics[0].jacobian(0).data.cols());
62 
63  for (int i = 0; i < kinematics[0].Phi.rows(); ++i)
64  {
65  phi(i) = kinematics[0].Phi(i).p.data[2];
66  jacobian.row(i) = kinematics[0].jacobian[i].data.middleRows<1>(2);
67  }
68 
69  if (debug_ && Server::IsRos()) PublishDebug();
70 }
71 
73 {
74  if (phi.rows() != kinematics[0].Phi.rows()) ThrowNamed("Wrong size of Phi!");
75  if (jacobian.rows() != kinematics[0].jacobian.rows() || jacobian.cols() != kinematics[0].jacobian(0).data.cols()) ThrowNamed("Wrong size of jacobian! " << kinematics[0].jacobian(0).data.cols());
76 
77  for (int i = 0; i < kinematics[0].Phi.rows(); ++i)
78  {
79  phi(i) = kinematics[0].Phi(i).p.data[2];
80  jacobian.row(i) = kinematics[0].jacobian[i].data.middleRows<1>(2);
81  hessian(i).block(0, 0, jacobian.cols(), jacobian.cols()) = kinematics[0].hessian[i](2);
82  }
83 }
84 
86 {
87  return kinematics[0].Phi.rows();
88 }
89 
91 {
92  visualization_msgs::MarkerArray msg;
93 
94  for (int i = 0; i < kinematics[0].Phi.rows(); ++i)
95  {
96  visualization_msgs::Marker plane;
97 
98  plane.header.frame_id = frames_[i].frame_B_link_name == "" ? "exotica/" + scene_->GetRootFrameName() : frames_[i].frame_B_link_name;
99  plane.ns = frames_[i].frame_A_link_name;
100  plane.id = i;
101  plane.type = plane.CUBE;
102  plane.action = plane.ADD;
103  plane.frame_locked = true;
104  plane.color.g = 1.0f;
105  plane.color.a = 0.8f;
106  tf::poseKDLToMsg(frames_[i].frame_B_offset, plane.pose);
107 
108  plane.scale.x = 10.f;
109  plane.scale.y = 10.f;
110  plane.scale.z = 0.01f;
111  plane.pose.position.z -= (plane.scale.z / 2);
112 
113  msg.markers.push_back(plane);
114  }
115 
116  debug_pub_.publish(msg);
117 }
118 } // namespace exotica
void Instantiate(const PointToPlaneInitializer &init) override
void publish(const boost::shared_ptr< M > &message) const
std::vector< KinematicFrameRequest > frames_
Eigen::Ref< Eigen::VectorXd > VectorXdRef
std::string object_name_
int TaskSpaceDim() override
#define ThrowNamed(m)
void Update(Eigen::VectorXdRefConst q, Eigen::VectorXdRef phi) override
const Eigen::Ref< const Eigen::VectorXd > & VectorXdRefConst
Eigen::Ref< Hessian > HessianRef
REGISTER_TASKMAP_TYPE("PointToPlane", exotica::PointToPlane)
Eigen::Ref< Eigen::MatrixXd > MatrixXdRef
void poseKDLToMsg(const KDL::Frame &k, geometry_msgs::Pose &m)
static bool IsRos()
ros::Publisher debug_pub_


exotica_core_task_maps
Author(s): Yiming Yang, Michael Camilleri
autogenerated on Sat Apr 10 2021 02:36:09