controllerclientcpp  0.6.1
 全て クラス ネームスペース ファイル 関数 変数 型定義 列挙型 列挙型の値 マクロ定義 ページ
binpickingtask.h
説明を見る。
1 // -*- coding: utf-8 -*-
2 // Copyright (C) 2012-2016 MUJIN Inc. <rosen.diankov@mujin.co.jp>
3 //
4 // Licensed under the Apache License, Version 2.0 (the "License");
5 // you may not use this file except in compliance with the License.
6 // You may obtain a copy of the License at
7 // http://www.apache.org/licenses/LICENSE-2.0
8 //
9 // Unless required by applicable law or agreed to in writing, software
10 // distributed under the License is distributed on an "AS IS" BASIS,
11 // WITHOUT WARRANTIES OR CONDITIONS OF ANY KIND, either express or implied.
12 // See the License for the specific language governing permissions and
13 // limitations under the License.
17 #ifndef MUJIN_CONTROLLERCLIENT_BINPICKINGTASK_H
18 #define MUJIN_CONTROLLERCLIENT_BINPICKINGTASK_H
19 
21 #include <boost/property_tree/ptree.hpp>
22 #include <boost/thread.hpp>
23 #ifdef MUJIN_USEZMQ
24 #include "zmq.hpp"
25 #endif
26 
27 namespace mujinclient {
28 
29 class MUJINCLIENT_API BinPickingResultResource : public PlanningResultResource
30 {
31 public:
32  BinPickingResultResource(ControllerClientPtr controller, const std::string& pk);
33 
35 
36  boost::property_tree::ptree GetResultPtree() const;
37 };
38 
39 class MUJINCLIENT_API BinPickingTaskResource : public TaskResource
40 {
41 public:
42  BinPickingTaskResource(ControllerClientPtr controller, const std::string& pk, const std::string& scenepk, const std::string& tasktype = "binpicking");
43  virtual ~BinPickingTaskResource();
44 
45  struct MUJINCLIENT_API DetectedObject
46  {
47  std::string name; // "name": "detectionresutl_1"
48  std::string object_uri; // "object_uri": "mujin:/box0.mujin.dae"
50  std::string confidence;
51  unsigned long long timestamp;
52  std::string extra; // (OPTIONAL) "extra": {"type":"randombox", "length":100, "width":100, "height":100}
53  };
54 
55  struct MUJINCLIENT_API PointCloudObstacle
56  {
57  std::string name;
58  std::vector<Real> points;
60  };
61 
62  struct MUJINCLIENT_API SensorOcclusionCheck
63  {
64  std::string bodyname;
65  std::string cameraname;
66  unsigned long long starttime;
67  unsigned long long endtime;
68  };
69 
70  struct MUJINCLIENT_API ResultBase
71  {
72  boost::property_tree::ptree _pt;
73 
74  virtual void Parse(const boost::property_tree::ptree& pt) = 0;
75  };
76  typedef boost::shared_ptr<ResultBase> ResultBasePtr;
77 
78  struct MUJINCLIENT_API ResultGetJointValues : public ResultBase
79  {
80  virtual ~ResultGetJointValues();
81  void Parse(const boost::property_tree::ptree& pt);
82  std::string robottype;
83  std::vector<std::string> jointnames;
84  std::vector<Real> currentjointvalues;
85  std::map<std::string, Transform> tools;
86  };
87 
88  struct MUJINCLIENT_API ResultMoveJoints : public ResultBase
89  {
90  virtual ~ResultMoveJoints();
91  void Parse(const boost::property_tree::ptree& pt);
92  std::string robottype;
93  int numpoints;
94  std::vector<Real> timedjointvalues;
95  //Real elapsedtime;
96  };
97 
98  struct MUJINCLIENT_API ResultTransform : public ResultBase
99  {
100  virtual ~ResultTransform();
101  void Parse(const boost::property_tree::ptree& pt);
103  };
104 
105  struct MUJINCLIENT_API ResultGetBinpickingState : public ResultBase
106  {
108  virtual ~ResultGetBinpickingState();
109  void Parse(const boost::property_tree::ptree& pt);
110  std::string statusPickPlace;
111  std::string statusDescPickPlace;
112  std::string statusPhysics;
116  unsigned long long timestamp;
117  unsigned long long lastGrabbedTargetTimeStamp;
126  std::vector<double> currentJointValues;
127  std::vector<double> currentToolValues;
128  std::vector<std::string> jointNames;
130  std::string robotbridgestatus;
131  };
132 
133  struct MUJINCLIENT_API ResultIsRobotOccludingBody : public ResultBase
134  {
135  virtual ~ResultIsRobotOccludingBody();
136  void Parse(const boost::property_tree::ptree& pt);
137  bool result;
138  };
139 
140  struct MUJINCLIENT_API ResultGetPickedPositions : public ResultBase
141  {
142  void Parse(const boost::property_tree::ptree& pt);
143  std::vector<Transform> transforms;
144  std::vector<unsigned long long> timestamps; // in millisecond
145  };
146 
147  struct MUJINCLIENT_API ResultAABB : public ResultBase
148  {
149  void Parse(const boost::property_tree::ptree& pt);
150  std::vector<Real> pos;
151  std::vector<Real> extents;
152  };
153 
154  struct MUJINCLIENT_API ResultOBB : public ResultBase
155  {
156  void Parse(const boost::property_tree::ptree& pt);
157  std::vector<Real> translation;
158  std::vector<Real> extents;
159  std::vector<Real> rotationmat; // row major
160  };
161 
162  struct MUJINCLIENT_API ResultGetInstObjectAndSensorInfo : public ResultBase
163  {
165  void Parse(const boost::property_tree::ptree& pt);
166  std::map<std::string, Transform> minstobjecttransform;
167  std::map<std::string, ResultOBB> minstobjectobb;
168  std::map<std::string, ResultOBB> minstobjectinnerobb;
169  std::map<std::string, Transform> msensortransform;
170  std::map<std::string, RobotResource::AttachedSensorResource::SensorData> msensordata;
171  };
172 
173  struct MUJINCLIENT_API ResultHeartBeat : public ResultBase
174  {
175  virtual ~ResultHeartBeat();
176  void Parse(const boost::property_tree::ptree& pt);
177  std::string status;
180  std::string msg;
181  std::string _slaverequestid;
182  };
183 
189  virtual void Initialize(const std::string& defaultTaskParameters, const double commandtimeout=0, const std::string& userinfo="{}", const std::string& slaverequestid="");
190 
191 #ifdef MUJIN_USEZMQ
192 
202  virtual void Initialize(const std::string& defaultTaskParameters, const int zmqPort, const int heartbeatPort, boost::shared_ptr<zmq::context_t> zmqcontext, const bool initializezmq=false, const double reinitializetimeout=10, const double commandtimeout=0, const std::string& userinfo="{}", const std::string& slaverequestid="");
203 #endif
204 
205  virtual boost::property_tree::ptree ExecuteCommand(const std::string& command, const double timeout /* second */=0.0, const bool getresult=true);
206 
207  virtual void GetJointValues(ResultGetJointValues& result, const double timeout /* second */=0);
208  virtual void MoveJoints(const std::vector<Real>& jointvalues, const std::vector<int>& jointindices, const Real envclearance, const Real speed /* 0.1-1 */, ResultMoveJoints& result, const double timeout /* second */=0);
209  virtual void GetTransform(const std::string& targetname, Transform& result, const std::string& unit="mm", const double timeout /* second */=0);
210  virtual void SetTransform(const std::string& targetname, const Transform& transform, const std::string& unit="mm", const double timeout /* second */=0);
211  virtual void GetManipTransformToRobot(Transform& result, const std::string& unit="mm", const double timeout /* second */=0);
212  virtual void GetManipTransform(Transform& result, const std::string& unit="mm", const double timeout /* second */=0);
213 
214  virtual void GetAABB(const std::string& targetname, ResultAABB& result, const std::string& unit="mm", const double timeout=0);
215  virtual void GetOBB(ResultOBB& result, const std::string& targetname, const std::string& linkname="", const std::string& unit="mm", const double timeout=0);
216  virtual void GetInnerEmptyRegionOBB(ResultOBB& result, const std::string& targetname, const std::string& linkname="", const std::string& unit="mm", const double timeout=0);
217 
226  virtual void UpdateObjects(const std::string& basename, const std::vector<Transform>& transformsworld, const std::vector<std::string>& confidence, const std::string& state, const std::string& unit="mm", const double timeout /* second */=0);
227 
233  virtual void InitializeZMQ(const double reinitializetimeout = 0,const double timeout /* second */=0);
234 
243  virtual void AddPointCloudObstacle(const std::vector<Real>& vpoints, const Real pointsize, const std::string& name, const unsigned long long starttimestamp=0, const unsigned long long endtimestamp=0, const bool executionverification=false, const std::string& unit="mm", int isoccluded=-1, const double timeout /* second */=0);
244 
245  virtual void UpdateEnvironmentState(const std::string& objectname, const std::vector<DetectedObject>& detectedobjects, const std::vector<Real>& vpoints, const std::string& resultstate, const Real pointsize, const std::string& pointcloudobstaclename, const std::string& unit="mm", const double timeout=0);
246 
254  virtual void VisualizePointCloud(const std::vector<std::vector<Real> >& pointslist, const Real pointsize, const std::vector<std::string>& names, const std::string& unit="m", const double timeout /* second */=0);
255 
258  virtual void ClearVisualization(const double timeout /* second */=0);
259 
264  virtual void IsRobotOccludingBody(const std::string& bodyname, const std::string& sensorname, const unsigned long long starttime, const unsigned long long endtime, bool& result, const double timeout /* second */=0);
265 
269  virtual void GetPickedPositions(ResultGetPickedPositions& result, const std::string& unit="m", const double timeout /* second */=0);
270 
271  virtual PlanningResultResourcePtr GetResult();
272 
277  virtual void GetInstObjectAndSensorInfo(const std::vector<std::string>& instobjectnames, const std::vector<std::string>& sensornames, ResultGetInstObjectAndSensorInfo& result, const std::string& unit="m", const double timeout /* second */=0);
278 
284  virtual void GetBinpickingState(ResultGetBinpickingState& result, const std::string& robotname, const std::string& unit="m", const double timeout /* second */=0);
285 
292  virtual void GetPublishedTaskState(ResultGetBinpickingState& result, const std::string& robotname, const std::string& unit="m", const double timeout /* second */=0);
293 
302  virtual void SetJogModeVelocities(const std::string& jogtype, const std::vector<int>& movejointsigns, const std::string& robotname = "", const std::string& toolname = "", const double robotspeed = -1, const double robotaccelmult = -1.0, const double timeout=1);
303 
311  virtual void MoveToolLinear(const std::string& goaltype, const std::vector<double>& goals, const std::string& robotname = "", const std::string& toolname = "", const double robotspeed = -1, const double timeout = 10);
312 
320  virtual void MoveToHandPosition(const std::string& goaltype, const std::vector<double>& goals, const std::string& robotname = "", const std::string& toolname = "", const double robotspeed = -1, const double timeout = 10);
321 
326  virtual void _HeartbeatMonitorThread(const double reinitializetimeout, const double commandtimeout);
327 
329  virtual const std::string& GetSlaveRequestId() const;
330 
331 protected:
332  std::stringstream _ss;
333 
334  std::map<std::string, std::string> _mapTaskParameters;
335  std::string _mujinControllerIp;
336  boost::mutex _mutexTaskState;
338 #ifdef MUJIN_USEZMQ
339  boost::shared_ptr<zmq::context_t> _zmqcontext;
340 #endif
341  int _zmqPort;
343  std::string _userinfo_json;
344  std::string _sceneparams_json;
345  std::string _slaverequestid;
346  std::string _scenepk;
347  const std::string _tasktype;
348  boost::shared_ptr<boost::thread> _pHeartbeatMonitorThread;
349 
352 
353 };
354 
355 namespace utils {
356 std::string GetJsonString(const std::string& string);
357 std::string GetJsonString(const std::vector<Real>& vec);
358 std::string GetJsonString(const std::vector<int>& vec);
359 std::string GetJsonString(const std::vector<std::string>& vec);
360 std::string GetJsonString(const Transform& transform);
364 
365 std::string GetJsonString(const std::string& key, const std::string& value);
366 std::string GetJsonString(const std::string& key, const int value);
367 std::string GetJsonString(const std::string& key, const unsigned long long value);
368 std::string GetJsonString(const std::string& key, const Real value);
369 
370 void GetAttachedSensors(ControllerClientPtr controller, SceneResourcePtr scene, const std::string& bodyname, std::vector<RobotResource::AttachedSensorResourcePtr>& result);
371 void GetSensorData(ControllerClientPtr controller, SceneResourcePtr scene, const std::string& bodyname, const std::string& sensorname, RobotResource::AttachedSensorResource::SensorData& result);
374 void GetSensorTransform(ControllerClientPtr controller, SceneResourcePtr scene, const std::string& bodyname, const std::string& sensorname, Transform& result, const std::string& unit="m");
375 void DeleteObject(SceneResourcePtr scene, const std::string& name);
376 void UpdateObjects(SceneResourcePtr scene, const std::string& basename, const std::vector<BinPickingTaskResource::DetectedObject>& detectedobjects, const std::string& unit="m");
377 
378 
379 #ifdef MUJIN_USEZMQ
380 
381 
382 
383 std::string GetHeartbeat(const std::string& endpoint);
384 
385 std::string GetScenePkFromHeatbeat(const std::string& heartbeat);
386 std::string GetSlaveRequestIdFromHeatbeat(const std::string& heartbeat);
387 #endif
388 }; // namespace utils
389 
390 } // namespace mujinclient
391 
392 #endif