controllerclientcpp  0.6.1
 全て クラス ネームスペース ファイル 関数 変数 型定義 列挙型 列挙型の値 マクロ定義 ページ
mujincontrollerclient.h
説明を見る。
1 // -*- coding: utf-8 -*-
2 // Copyright (C) 2012-2013 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_H
18 #define MUJIN_CONTROLLERCLIENT_H
19 
20 #ifndef MUJINCLIENT_DISABLE_ASSERT_HANDLER
21 #define BOOST_ENABLE_ASSERT_HANDLER
22 #endif
23 
24 #ifdef _MSC_VER
25 
26 #pragma warning(disable:4251) // needs to have dll-interface to be used by clients of class
27 #pragma warning(disable:4190) // C-linkage specified, but returns UDT 'boost::shared_ptr<T>' which is incompatible with C
28 #pragma warning(disable:4819) //The file contains a character that cannot be represented in the current code page (932). Save the file in Unicode format to prevent data loss using native typeof
29 
30 #ifndef __PRETTY_FUNCTION__
31 #define __PRETTY_FUNCTION__ __FUNCDNAME__
32 #endif
33 
34 #else
35 #endif
36 
37 #if defined(__GNUC__)
38 #define MUJINCLIENT_DEPRECATED __attribute__((deprecated))
39 #else
40 #define MUJINCLIENT_DEPRECATED
41 #endif
42 
43 #include <string>
44 #include <vector>
45 #include <list>
46 #include <map>
47 #include <set>
48 #include <string>
49 #include <exception>
50 
51 #include <iomanip>
52 #include <fstream>
53 #include <sstream>
54 
55 #include <boost/version.hpp>
56 #include <boost/shared_ptr.hpp>
57 #include <boost/weak_ptr.hpp>
58 #include <boost/format.hpp>
59 #include <boost/array.hpp>
60 #include <boost/property_tree/ptree.hpp>
61 
62 namespace mujinclient {
63 
64 #include <mujincontrollerclient/config.h>
65 
81 };
82 
84 {
86 };
87 
88 inline const char* GetErrorCodeString(MujinErrorCode error)
89 {
90  switch(error) {
91  case MEC_Failed: return "Failed";
92  case MEC_InvalidArguments: return "InvalidArguments";
93  case MEC_CommandNotSupported: return "CommandNotSupported";
94  case MEC_Assert: return "Assert";
95  case MEC_NotInitialized: return "NotInitialized";
96  case MEC_InvalidState: return "InvalidState";
97  case MEC_Timeout: return "Timeout";
98  case MEC_HTTPClient: return "HTTPClient";
99  case MEC_HTTPServer: return "HTTPServer";
100  case MEC_UserAuthentication: return "UserAuthentication";
101  case MEC_AlreadyExists: return "AlreadyExists";
102  case MEC_BinPickingError: return "BinPickingError";
103  case MEC_HandEyeCalibrationError: return "HandEyeCalibrationError";
104  case MEC_ZMQNoResponse: return "NoResponse";
105  }
106  // should throw an exception?
107  return "";
108 }
109 
111 class MUJINCLIENT_API MujinException : public std::exception
112 {
113 public:
114  MujinException() : std::exception(), _s("unknown exception"), _error(MEC_Failed) {
115  }
116  MujinException(const std::string& s, MujinErrorCode error=MEC_Failed) : std::exception() {
117  _error = error;
118  _s = "mujin (";
119  _s += GetErrorCodeString(_error);
120  _s += "): ";
121  _s += s;
122  }
123  virtual ~MujinException() throw() {
124  }
125  char const* what() const throw() {
126  return _s.c_str();
127  }
128  const std::string& message() const {
129  return _s;
130  }
132  return _error;
133  }
134 private:
135  std::string _s;
136  MujinErrorCode _error;
137 };
138 
139 class ControllerClient;
140 class ObjectResource;
141 class RobotResource;
142 class SceneResource;
143 class TaskResource;
144 class BinPickingTaskResource;
145 class OptimizationResource;
146 class PlanningResultResource;
148 
149 typedef boost::shared_ptr<ControllerClient> ControllerClientPtr;
150 typedef boost::weak_ptr<ControllerClient> ControllerClientWeakPtr;
151 typedef boost::shared_ptr<ObjectResource> ObjectResourcePtr;
152 typedef boost::weak_ptr<ObjectResource> ObjectResourceWeakPtr;
153 typedef boost::shared_ptr<RobotResource> RobotResourcePtr;
154 typedef boost::weak_ptr<RobotResource> RobotResourceWeakPtr;
155 typedef boost::shared_ptr<SceneResource> SceneResourcePtr;
156 typedef boost::weak_ptr<SceneResource> SceneResourceWeakPtr;
157 typedef boost::shared_ptr<TaskResource> TaskResourcePtr;
158 typedef boost::weak_ptr<TaskResource> TaskResourceWeakPtr;
159 typedef boost::shared_ptr<BinPickingTaskResource> BinPickingTaskResourcePtr;
160 typedef boost::weak_ptr<BinPickingTaskResource> BinPickingTaskResourceWeakPtr;
161 typedef boost::shared_ptr<OptimizationResource> OptimizationResourcePtr;
162 typedef boost::weak_ptr<OptimizationResource> OptimizationResourceWeakPtr;
163 typedef boost::shared_ptr<PlanningResultResource> PlanningResultResourcePtr;
164 typedef boost::weak_ptr<PlanningResultResource> PlanningResultResourceWeakPtr;
165 typedef boost::shared_ptr<BinPickingResultResource> BinPickingResultResourcePtr;
166 typedef boost::weak_ptr<BinPickingResultResource> BinPickingResultResourceWeakPtr;
167 typedef double Real;
168 
182  JSC_Lost = 9,
183  JSC_Unknown = 0xffffffff,
184 };
185 
186 struct JobStatus
187 {
189  }
191  std::string type;
192  std::string message;
193  double elapsedtime;
194  std::string pk;
195 };
196 
198 struct Transform
199 {
201  quaternion[0] = 1; quaternion[1] = 0; quaternion[2] = 0; quaternion[3] = 0;
202  translate[0] = 0; translate[1] = 0; translate[2] = 0;
203  }
206 };
207 
209 {
211  std::vector<Real> dofvalues;
212 };
213 
214 typedef std::map<std::string, InstanceObjectState> EnvironmentState;
215 
217 {
218  std::string pk;
219  std::string uri;
220  std::string datemodified;
221  std::string name;
222 };
223 
226 {
227 public:
229  SetDefaults();
230  }
231  virtual void SetDefaults() {
232  startfromcurrent = 0;
233  returnmode = "start";
234  vrcruns = 1;
235  ignorefigure = 1;
236  unit = "mm";
237  optimizationvalue = 1;
238  program.clear();
239  }
240 
242 
247  std::string returnmode;
248 
249  int vrcruns;
251  std::string unit;
253  std::string program;
254 
257 };
258 
261 {
262 public:
264  SetDefaults();
265  }
266  void SetDefaults() {
269  }
271 };
272 
275 {
277  SetDefaults();
278  }
279  inline void SetDefaults() {
280  unit = "mm";
281  topstorecandidates = 20;
282  targetname.clear();
283  framename.clear();
284  minrange[0] = -400; minrange[1] = -400; minrange[2] = 0; minrange[3] = -180;
285  maxrange[0] = 400; maxrange[1] = 400; maxrange[2] = 400; maxrange[3] = 90;
286  stepsize[0] = 100; stepsize[1] = 100; stepsize[2] = 100; stepsize[3] = 90;
288  }
289  std::string targetname;
290  std::string framename;
295 
296  std::string unit;
298 };
299 
301 {
303  SetDefaults();
304  }
305  inline void SetDefaults() {
306  unit = "mm";
307  topstorecandidates = 20;
308  for(size_t itarget = 0; itarget < targetnames.size(); ++itarget) {
309  targetnames[itarget].clear();
310  framenames[itarget].clear();
311  ignorebasecollisions[itarget] = 0;
312  }
313  minranges[0][0] = -400; minranges[0][1] = -400; minranges[0][2] = 0; minranges[0][3] = -180;
314  maxranges[0][0] = 400; maxranges[0][1] = 400; maxranges[0][2] = 400; maxranges[0][3] = 90;
315  stepsizes[0][0] = 100; stepsizes[0][1] = 100; stepsizes[0][2] = 100; stepsizes[0][3] = 90;
316  minranges[1][0] = -100; minranges[1][1] = -100; minranges[1][2] = 0; minranges[1][3] = 0;
317  maxranges[1][0] = 100; maxranges[1][1] = 100; maxranges[1][2] = 100; maxranges[1][3] = 0;
318  stepsizes[1][0] = 100; stepsizes[1][1] = 100; stepsizes[1][2] = 100; stepsizes[1][3] = 90;
319  }
320 
321  // for every target, there's one setting:
322  boost::array<std::string, 2> targetnames;
323  boost::array<std::string, 2> framenames;
324  boost::array<Real[4],2> maxranges;
325  boost::array<Real[4],2> minranges;
326  boost::array<Real[4],2> stepsizes;
327  boost::array<int,2> ignorebasecollisions;
328 
329  // shared settings
330  std::string unit;
332 };
333 
336 {
337 public:
339  }
340  RobotProgramData(const std::string& programdata, const std::string& type) : programdata(programdata), type(type) {
341  }
342  std::string programdata;
343  std::string type;
344 };
345 
348 {
349 public:
350  std::map<std::string, RobotProgramData> programs;
351 };
352 
356 class MUJINCLIENT_API ControllerClient
357 {
358 public:
359  virtual ~ControllerClient() {
360  }
361 
362 // \brief Returns a list of filenames in the user system of a particular type
363 //
364 // \param scenetype the type of scene possible values are:
365 // - mujincollada
366 // - wincaps
367 // - rttoolbox
368 // - cecrobodiaxml
369 // - stl
370 // - x
371 // - vrml
372 // - stl
373 //
374 // virtual void GetSceneFilenames(const std::string& scenetype, std::vector<std::string>& scenefilenames) = 0;
375 
380  virtual void SetCharacterEncoding(const std::string& newencoding) = 0;
381 
385  virtual void SetLanguage(const std::string& language) = 0;
386 
388  virtual const std::string& GetUserName() const = 0;
389 
394  virtual void SetProxy(const std::string& serverport, const std::string& userpw) = 0;
395 
400  virtual void RestartServer() = 0;
401 
403  virtual void Upgrade(const std::vector<unsigned char>& vdata) = 0;
404 
406  virtual std::string GetVersion() = 0;
407 
411  virtual void CancelAllJobs() = 0;
412 
416  virtual void GetRunTimeStatuses(std::vector<JobStatus>& statuses, int options=0) = 0;
417 
419  virtual void GetScenePrimaryKeys(std::vector<std::string>& scenekeys) = 0;
420 
433  virtual SceneResourcePtr RegisterScene_UTF8(const std::string& uri, const std::string& scenetype) = 0;
434 
436  virtual SceneResourcePtr RegisterScene_UTF8(const std::string& uri)
437  {
438  return RegisterScene_UTF8(uri,GetDefaultSceneType());
439  }
440 
444  virtual SceneResourcePtr RegisterScene_UTF16(const std::wstring& uri, const std::string& scenetype) = 0;
445 
447  virtual SceneResourcePtr RegisterScene_UTF16(const std::wstring& uri)
448  {
449  return RegisterScene_UTF16(uri,GetDefaultSceneType());
450  }
451 
466  virtual SceneResourcePtr ImportSceneToCOLLADA_UTF8(const std::string& sourceuri, const std::string& sourcescenetype, const std::string& newuri, bool overwrite=false) = 0;
467 
472  virtual SceneResourcePtr ImportSceneToCOLLADA_UTF16(const std::wstring& sourceuri, const std::string& sourcescenetype, const std::wstring& newuri, bool overwrite=false) = 0;
473 
482  virtual void SyncUpload_UTF8(const std::string& sourcefilename, const std::string& destinationdir, const std::string& scenetype) = 0;
483 
485  virtual void SyncUpload_UTF8(const std::string& sourcefilename, const std::string& destinationdir)
486  {
487  SyncUpload_UTF8(sourcefilename, destinationdir, GetDefaultSceneType());
488  }
489 
495  virtual void SyncUpload_UTF16(const std::wstring& sourcefilename, const std::wstring& destinationdir, const std::string& scenetype) = 0;
496 
498  virtual void SyncUpload_UTF16(const std::wstring& sourcefilename, const std::wstring& destinationdir)
499  {
500  SyncUpload_UTF16(sourcefilename, destinationdir, GetDefaultSceneType());
501  }
502 
508  virtual void UploadFileToController_UTF8(const std::string& filename, const std::string& desturi) = 0;
509 
514  virtual void UploadFileToController_UTF16(const std::wstring& filename, const std::wstring& desturi) = 0;
515 
521  virtual void UploadDataToController_UTF8(const std::vector<unsigned char>& vdata, const std::string& desturi) = 0;
522 
530  virtual void UploadDirectoryToController_UTF8(const std::string& copydir, const std::string& desturi) = 0;
531 
536  virtual void UploadDirectoryToController_UTF16(const std::wstring& copydir, const std::wstring& desturi) = 0;
537 
539  virtual void DownloadFileFromController_UTF8(const std::string& desturi, std::vector<unsigned char>& vdata) = 0;
541  virtual void DownloadFileFromController_UTF16(const std::wstring& desturi, std::vector<unsigned char>& vdata) = 0;
542 
546  virtual void DownloadFileFromControllerIfModifiedSince_UTF8(const std::string& desturi, long localtimeval, long &remotetimeval, std::vector<unsigned char>& vdata) = 0;
547 
551  virtual void DownloadFileFromControllerIfModifiedSince_UTF16(const std::wstring& desturi, long localtimeval, long &remotetimeval, std::vector<unsigned char>& vdata) = 0;
552 
556  virtual void DeleteFileOnController_UTF8(const std::string& uri) = 0;
557 
561  virtual void DeleteFileOnController_UTF16(const std::wstring& uri) = 0;
562 
566  virtual void DeleteDirectoryOnController_UTF8(const std::string& uri) = 0;
567 
571  virtual void DeleteDirectoryOnController_UTF16(const std::wstring& uri) = 0;
572 
573  virtual void SetDefaultSceneType(const std::string& scenetype) = 0;
574 
575  virtual const std::string& GetDefaultSceneType() = 0;
576 
577  virtual void SetDefaultTaskType(const std::string& tasktype) = 0;
578 
579  virtual const std::string& GetDefaultTaskType() = 0;
580 
594  virtual std::string GetScenePrimaryKeyFromURI_UTF8(const std::string& uri) = 0;
595 
603  virtual std::string GetScenePrimaryKeyFromURI_UTF16(const std::wstring& uri) = 0;
604 
608  virtual std::string GetPrimaryKeyFromName_UTF8(const std::string& name) = 0;
609 
613  virtual std::string GetPrimaryKeyFromName_UTF16(const std::wstring& name) = 0;
614 
618  virtual std::string GetNameFromPrimaryKey_UTF8(const std::string& pk) = 0;
619 
623  virtual std::wstring GetNameFromPrimaryKey_UTF16(const std::string& pk) = 0;
624 };
625 
626 class MUJINCLIENT_API WebResource
627 {
628 public:
629  WebResource(ControllerClientPtr controller, const std::string& resourcename, const std::string& pk);
630  virtual ~WebResource() {
631  }
632 
634  return __controller;
635  }
636  inline const std::string& GetResourceName() const {
637  return __resourcename;
638  }
639  inline const std::string& GetPrimaryKey() const {
640  return __pk;
641  }
642 
644  virtual std::string Get(const std::string& field);
645 
647  virtual void Set(const std::string& field, const std::string& newvalue);
648 
650  virtual void Delete();
651 
653  virtual void Copy(const std::string& newname, int options);
654 
655 private:
656  ControllerClientPtr __controller;
657  std::string __resourcename, __pk;
658 };
659 
660 class MUJINCLIENT_API ObjectResource : public WebResource
661 {
662 public:
663  class MUJINCLIENT_API LinkResource : public WebResource {
664 public:
665  LinkResource(ControllerClientPtr controller, const std::string& objectpk, const std::string& pk);
666  virtual ~LinkResource() {
667  }
668 
669  std::vector<std::string> attachmentpks;
670  std::string name;
671  std::string pk;
672  //TODO transforms
673  };
674  typedef boost::shared_ptr<LinkResource> LinkResourcePtr;
675 
676  ObjectResource(ControllerClientPtr controller, const std::string& pk);
677  virtual ~ObjectResource() {
678  }
679 
680  virtual void GetLinks(std::vector<LinkResourcePtr>& links);
681 
682  std::string name;
683  int nundof;
684  std::string datemodified;
685  std::string geometry;
686  bool isrobot;
687  std::string pk;
688  std::string resource_uri;
689  std::string scenepk;
690  std::string unit;
691  std::string uri;
692 
693 protected:
694  ObjectResource(ControllerClientPtr controller, const std::string& resource, const std::string& pk);
695 
696 };
697 
698 class MUJINCLIENT_API RobotResource : public ObjectResource
699 {
700 public:
701  class MUJINCLIENT_API ToolResource : public WebResource {
702 public:
703  ToolResource(ControllerClientPtr controller, const std::string& robotobjectpk, const std::string& pk);
704  virtual ~ToolResource() {
705  }
706 
707  std::string name;
708  std::string frame_origin;
709  std::string frame_tip;
710  std::string pk;
711  Real direction[3];
712  Real quaternion[4]; // quaternion [w, x, y, z] = [cos(angle/2), sin(angle/2)*rotation_axis]
713  Real translate[3];
714  };
715  typedef boost::shared_ptr<ToolResource> ToolResourcePtr;
716 
717  class MUJINCLIENT_API AttachedSensorResource : public WebResource {
718 public:
719  AttachedSensorResource(ControllerClientPtr controller, const std::string& robotobjectpk, const std::string& pk);
721  }
722 
723  std::string name;
724  std::string frame_origin;
725  std::string pk;
726  //Real direction[3];
727  Real quaternion[4]; // quaternion [w, x, y, z] = [cos(angle/2), sin(angle/2)*rotation_axis]
728  Real translate[3];
729  std::string sensortype;
730 
731  class SensorData {
732 public:
733  Real distortion_coeffs[5];
734  std::string distortion_model;
736  int image_dimensions[3];
737  Real intrinsic[6];
739  std::vector<Real> extra_parameters;
740  };
742  };
743 
744  typedef boost::shared_ptr<AttachedSensorResource> AttachedSensorResourcePtr;
745 
746  RobotResource(ControllerClientPtr controller, const std::string& pk);
747  virtual ~RobotResource() {
748  }
749 
750  virtual void GetTools(std::vector<ToolResourcePtr>& tools);
751  virtual void GetAttachedSensors(std::vector<AttachedSensorResourcePtr>& attachedsensors);
752 
753  // attachments
754  // ikparams
755  // images
756  int numdof;
757  std::string simulation_file;
758 };
759 
760 class MUJINCLIENT_API SceneResource : public WebResource
761 {
762 public:
763  class InstObject;
764  typedef boost::shared_ptr<InstObject> InstObjectPtr;
766  class MUJINCLIENT_API InstObject : public WebResource
767  {
768 public:
769  InstObject(ControllerClientPtr controller, const std::string& scenepk, const std::string& pk);
770  virtual ~InstObject() {
771  }
772 
773  class MUJINCLIENT_API Link {
774 public:
775  std::string name;
776  Real quaternion[4]; // quaternion [w, x, y, z] = [cos(angle/2), sin(angle/2)*rotation_axis]
777  Real translate[3];
778  };
779 
780  class MUJINCLIENT_API Tool {
781 public:
782  std::string name;
783  Real direction[3];
784  Real quaternion[4]; // quaternion [w, x, y, z] = [cos(angle/2), sin(angle/2)*rotation_axis]
785  Real translate[3];
786  };
787 
788  class MUJINCLIENT_API Grab {
789 public:
790  std::string instobjectpk;
791  std::string grabbed_linkpk;
792  std::string grabbing_linkpk;
793 
794  std::string Serialize() {
795  return boost::str(boost::format("{\"instobjectpk\": \"%s\", \"grabbed_linkpk\": \"%s\", \"grabbing_linkpk\": \"%s\"}")%instobjectpk%grabbed_linkpk%grabbing_linkpk);
796  }
797 
798  bool operator==(const Grab grab) {
799  if (this->instobjectpk == grab.instobjectpk
800  && this->grabbed_linkpk == grab.grabbed_linkpk
801  && this->grabbing_linkpk == grab.grabbing_linkpk) {
802  return true;
803  }
804  return false;
805  }
806  };
807 
808  class MUJINCLIENT_API AttachedSensor {
809 public:
810  std::string name;
811  Real quaternion[4]; // quaternion [w, x, y, z] = [cos(angle/2), sin(angle/2)*rotation_axis]
812  Real translate[3];
813  };
814 
815  void SetTransform(const Transform& t);
816  void SetDOFValues();
817  virtual void GrabObject(InstObjectPtr grabbedobject, std::string& grabbedobjectlinkpk, std::string& grabbinglinkpk);
818  virtual void ReleaseObject(InstObjectPtr grabbedobject, std::string& grabbedobjectlinkpk, std::string& grabbinglinkpk);
819 
820 
821  std::vector<Real> dofvalues;
822  std::string name;
823  std::string pk;
824  std::string object_pk;
825  std::string reference_uri;
826  Real quaternion[4]; // quaternion [w, x, y, z] = [cos(angle/2), sin(angle/2)*rotation_axis]
827  Real translate[3];
828  std::vector<Grab> grabs;
829  std::vector<Link> links;
830  std::vector<Tool> tools;
831  std::vector<AttachedSensor> attachedsensors;
832  };
833 
834  SceneResource(ControllerClientPtr controller, const std::string& pk);
835  virtual ~SceneResource() {
836  }
837 
838  virtual void SetInstObjectsState(const std::vector<SceneResource::InstObjectPtr>& instobjects, const std::vector<InstanceObjectState>& states);
839 
848  virtual TaskResourcePtr GetOrCreateTaskFromName_UTF8(const std::string& taskname, const std::string& tasktype, int options=0);
849 
850  virtual TaskResourcePtr GetOrCreateTaskFromName_UTF8(const std::string& taskname, int options=0)
851  {
852  return GetOrCreateTaskFromName_UTF8(taskname, GetController()->GetDefaultTaskType(), options);
853  }
854 
855  virtual TaskResourcePtr GetTaskFromName_UTF8(const std::string& taskname, int options=0);
856 
864  virtual TaskResourcePtr GetOrCreateTaskFromName_UTF16(const std::wstring& taskname, const std::string& tasktype, int options=0);
865 
866  virtual TaskResourcePtr GetOrCreateTaskFromName_UTF16(const std::wstring& taskname, int options=0)
867  {
868  return GetOrCreateTaskFromName_UTF16(taskname, GetController()->GetDefaultTaskType(), options);
869  }
870 
871  virtual TaskResourcePtr GetTaskFromName_UTF16(const std::wstring& taskname, int options=0);
872 
873 
874  virtual BinPickingTaskResourcePtr GetOrCreateBinPickingTaskFromName_UTF8(const std::string& taskname, const std::string& tasktype="binpicking", int options=0);
875  virtual BinPickingTaskResourcePtr GetOrCreateBinPickingTaskFromName_UTF16(const std::wstring& taskname, const std::string& tasktype="binpicking", int options=0);
876 
877 
879  virtual void GetTaskPrimaryKeys(std::vector<std::string>& taskkeys);
880 
882  virtual void GetSensorMapping(std::map<std::string, std::string>& sensormapping);
883  virtual void GetInstObjects(std::vector<InstObjectPtr>& instobjects);
884  virtual bool FindInstObject(const std::string& name, InstObjectPtr& instobject);
885 
886  virtual SceneResource::InstObjectPtr CreateInstObject(const std::string& name, const std::string& reference_uri, Real quaternion[4], Real translate[3]);
887 
888  virtual SceneResourcePtr Copy(const std::string& name);
889 };
890 
891 class MUJINCLIENT_API TaskResource : public WebResource
892 {
893 public:
894  TaskResource(ControllerClientPtr controller, const std::string& pk);
895  virtual ~TaskResource() {
896  }
897 
902  virtual bool Execute();
903 
905  virtual void Cancel();
906 
912  virtual void GetRunTimeStatus(JobStatus& status, int options = 1);
913 
918  virtual OptimizationResourcePtr GetOrCreateOptimizationFromName_UTF8(const std::string& optimizationname, const std::string& optimizationtype=std::string("robotplacement"));
919 
921  virtual OptimizationResourcePtr GetOrCreateOptimizationFromName_UTF16(const std::wstring& optimizationname, const std::string& optimizationtype=std::string("robotplacement"));
922 
924  virtual void GetOptimizationPrimaryKeys(std::vector<std::string>& optimizationkeys);
925 
927  virtual void GetTaskParameters(ITLPlanningTaskParameters& taskparameters);
928 
930  virtual void SetTaskParameters(const ITLPlanningTaskParameters& taskparameters);
931 
933  virtual PlanningResultResourcePtr GetResult();
934 
935 protected:
936  std::string _jobpk;
937 };
938 
939 class MUJINCLIENT_API OptimizationResource : public WebResource
940 {
941 public:
942  OptimizationResource(ControllerClientPtr controller, const std::string& pk);
944  }
945 
949  virtual void Execute(bool bClearOldResults=true);
950 
952  virtual void Cancel();
953 
955  void SetOptimizationParameters(const RobotPlacementOptimizationParameters& optparams);
956 
958  void SetOptimizationParameters(const PlacementsOptimizationParameters& optparams);
959 
965  virtual void GetRunTimeStatus(JobStatus& status, int options = 1);
966 
971  virtual void GetResults(std::vector<PlanningResultResourcePtr>& results, int startoffset=0, int num=0);
972 
973 protected:
974  std::string _jobpk;
975 };
976 
977 class MUJINCLIENT_API PlanningResultResource : public WebResource
978 {
979 public:
980  PlanningResultResource(ControllerClientPtr controller, const std::string& resulttype, const std::string& pk);
981  PlanningResultResource(ControllerClientPtr controller, const std::string& pk);
983  }
984 
986  virtual void GetEnvironmentState(EnvironmentState& envstate);
987 
1001  virtual void GetAllRawProgramData(std::string& outputdata, const std::string& programtype="auto");
1002 
1010  virtual void GetRobotRawProgramData(std::string& outputdata, const std::string& robotpk, const std::string& programtype="auto");
1011 
1017  virtual void GetPrograms(RobotControllerPrograms& programs, const std::string& programtype="auto");
1018 };
1019 
1038 MUJINCLIENT_API ControllerClientPtr CreateControllerClient(const std::string& usernamepassword, const std::string& url=std::string(), const std::string& proxyserverport=std::string(), const std::string& proxyuserpw=std::string(), int options=0);
1039 
1041 MUJINCLIENT_API void DestroyControllerClient();
1042 
1044 MUJINCLIENT_API void ControllerClientDestroy() MUJINCLIENT_DEPRECATED;
1045 
1047 MUJINCLIENT_API void ComputeMatrixFromTransform(Real matrix[12], const Transform &transform);
1048 
1061 MUJINCLIENT_API void ComputeZXYFromMatrix(Real ZXY[3], const Real matrix[12]);
1062 
1063 MUJINCLIENT_API void ComputeZXYFromTransform(Real ZXY[3], const Transform &transform);
1064 
1065 MUJINCLIENT_API void SerializeEnvironmentStateToJSON(const EnvironmentState& envstate, std::ostream& os);
1066 
1067 }
1068 
1069 #if !defined(MUJINCLIENT_DISABLE_ASSERT_HANDLER) && defined(BOOST_ENABLE_ASSERT_HANDLER)
1070 
1071 namespace boost
1072 {
1073 inline void assertion_failed(char const * expr, char const * function, char const * file, long line)
1074 {
1075  throw mujinclient::MujinException(boost::str(boost::format("[%s:%d] -> %s, expr: %s")%file%line%function%expr),mujinclient::MEC_Assert);
1076 }
1077 
1078 #if BOOST_VERSION>104600
1079 inline void assertion_failed_msg(char const * expr, char const * msg, char const * function, char const * file, long line)
1080 {
1081  throw mujinclient::MujinException(boost::str(boost::format("[%s:%d] -> %s, expr: %s, msg: %s")%file%line%function%expr%msg),mujinclient::MEC_Assert);
1082 }
1083 #endif
1084 
1085 }
1086 #endif
1087 
1088 BOOST_STATIC_ASSERT(MUJINCLIENT_VERSION_MAJOR>=0&&MUJINCLIENT_VERSION_MAJOR<=255);
1089 BOOST_STATIC_ASSERT(MUJINCLIENT_VERSION_MINOR>=0&&MUJINCLIENT_VERSION_MINOR<=255);
1090 BOOST_STATIC_ASSERT(MUJINCLIENT_VERSION_PATCH>=0&&MUJINCLIENT_VERSION_PATCH<=255);
1091 
1092 #endif