$search
00001 """autogenerated by genmsg_py from SetPhysicsPropertiesRequest.msg. Do not edit.""" 00002 import roslib.message 00003 import struct 00004 00005 import gazebo.msg 00006 import geometry_msgs.msg 00007 00008 class SetPhysicsPropertiesRequest(roslib.message.Message): 00009 _md5sum = "46d5128757a51ad3b4801be86612b17c" 00010 _type = "gazebo/SetPhysicsPropertiesRequest" 00011 _has_header = False #flag to mark the presence of a Header object 00012 _full_text = """ 00013 00014 00015 float64 time_step 00016 bool pause 00017 float64 max_update_rate 00018 geometry_msgs/Vector3 gravity 00019 gazebo/ODEPhysics ode_config 00020 00021 ================================================================================ 00022 MSG: geometry_msgs/Vector3 00023 # This represents a vector in free space. 00024 00025 float64 x 00026 float64 y 00027 float64 z 00028 ================================================================================ 00029 MSG: gazebo/ODEPhysics 00030 #This message is deprecated. Please use the version in gazebo_msgs instead. 00031 00032 bool auto_disable_bodies # enable auto disabling of bodies, default false 00033 uint32 sor_pgs_iters # inner iterations when uisng projected Gauss Seidel 00034 float64 sor_pgs_w # relaxation parameter when using projected Gauss Seidel, 1 = no relaxation 00035 float64 contact_surface_layer # contact "dead-band" width 00036 float64 contact_max_correcting_vel # contact maximum correction velocity 00037 float64 cfm # global constraint force mixing 00038 float64 erp # global error reduction parameter 00039 uint32 max_contacts # maximum contact joints between two geoms 00040 00041 """ 00042 __slots__ = ['time_step','pause','max_update_rate','gravity','ode_config'] 00043 _slot_types = ['float64','bool','float64','geometry_msgs/Vector3','gazebo/ODEPhysics'] 00044 00045 def __init__(self, *args, **kwds): 00046 """ 00047 Constructor. Any message fields that are implicitly/explicitly 00048 set to None will be assigned a default value. The recommend 00049 use is keyword arguments as this is more robust to future message 00050 changes. You cannot mix in-order arguments and keyword arguments. 00051 00052 The available fields are: 00053 time_step,pause,max_update_rate,gravity,ode_config 00054 00055 @param args: complete set of field values, in .msg order 00056 @param kwds: use keyword arguments corresponding to message field names 00057 to set specific fields. 00058 """ 00059 if args or kwds: 00060 super(SetPhysicsPropertiesRequest, self).__init__(*args, **kwds) 00061 #message fields cannot be None, assign default values for those that are 00062 if self.time_step is None: 00063 self.time_step = 0. 00064 if self.pause is None: 00065 self.pause = False 00066 if self.max_update_rate is None: 00067 self.max_update_rate = 0. 00068 if self.gravity is None: 00069 self.gravity = geometry_msgs.msg.Vector3() 00070 if self.ode_config is None: 00071 self.ode_config = gazebo.msg.ODEPhysics() 00072 else: 00073 self.time_step = 0. 00074 self.pause = False 00075 self.max_update_rate = 0. 00076 self.gravity = geometry_msgs.msg.Vector3() 00077 self.ode_config = gazebo.msg.ODEPhysics() 00078 00079 def _get_types(self): 00080 """ 00081 internal API method 00082 """ 00083 return self._slot_types 00084 00085 def serialize(self, buff): 00086 """ 00087 serialize message into buffer 00088 @param buff: buffer 00089 @type buff: StringIO 00090 """ 00091 try: 00092 _x = self 00093 buff.write(_struct_dB4dBI5dI.pack(_x.time_step, _x.pause, _x.max_update_rate, _x.gravity.x, _x.gravity.y, _x.gravity.z, _x.ode_config.auto_disable_bodies, _x.ode_config.sor_pgs_iters, _x.ode_config.sor_pgs_w, _x.ode_config.contact_surface_layer, _x.ode_config.contact_max_correcting_vel, _x.ode_config.cfm, _x.ode_config.erp, _x.ode_config.max_contacts)) 00094 except struct.error as se: self._check_types(se) 00095 except TypeError as te: self._check_types(te) 00096 00097 def deserialize(self, str): 00098 """ 00099 unpack serialized message in str into this message instance 00100 @param str: byte array of serialized message 00101 @type str: str 00102 """ 00103 try: 00104 if self.gravity is None: 00105 self.gravity = geometry_msgs.msg.Vector3() 00106 if self.ode_config is None: 00107 self.ode_config = gazebo.msg.ODEPhysics() 00108 end = 0 00109 _x = self 00110 start = end 00111 end += 90 00112 (_x.time_step, _x.pause, _x.max_update_rate, _x.gravity.x, _x.gravity.y, _x.gravity.z, _x.ode_config.auto_disable_bodies, _x.ode_config.sor_pgs_iters, _x.ode_config.sor_pgs_w, _x.ode_config.contact_surface_layer, _x.ode_config.contact_max_correcting_vel, _x.ode_config.cfm, _x.ode_config.erp, _x.ode_config.max_contacts,) = _struct_dB4dBI5dI.unpack(str[start:end]) 00113 self.pause = bool(self.pause) 00114 self.ode_config.auto_disable_bodies = bool(self.ode_config.auto_disable_bodies) 00115 return self 00116 except struct.error as e: 00117 raise roslib.message.DeserializationError(e) #most likely buffer underfill 00118 00119 00120 def serialize_numpy(self, buff, numpy): 00121 """ 00122 serialize message with numpy array types into buffer 00123 @param buff: buffer 00124 @type buff: StringIO 00125 @param numpy: numpy python module 00126 @type numpy module 00127 """ 00128 try: 00129 _x = self 00130 buff.write(_struct_dB4dBI5dI.pack(_x.time_step, _x.pause, _x.max_update_rate, _x.gravity.x, _x.gravity.y, _x.gravity.z, _x.ode_config.auto_disable_bodies, _x.ode_config.sor_pgs_iters, _x.ode_config.sor_pgs_w, _x.ode_config.contact_surface_layer, _x.ode_config.contact_max_correcting_vel, _x.ode_config.cfm, _x.ode_config.erp, _x.ode_config.max_contacts)) 00131 except struct.error as se: self._check_types(se) 00132 except TypeError as te: self._check_types(te) 00133 00134 def deserialize_numpy(self, str, numpy): 00135 """ 00136 unpack serialized message in str into this message instance using numpy for array types 00137 @param str: byte array of serialized message 00138 @type str: str 00139 @param numpy: numpy python module 00140 @type numpy: module 00141 """ 00142 try: 00143 if self.gravity is None: 00144 self.gravity = geometry_msgs.msg.Vector3() 00145 if self.ode_config is None: 00146 self.ode_config = gazebo.msg.ODEPhysics() 00147 end = 0 00148 _x = self 00149 start = end 00150 end += 90 00151 (_x.time_step, _x.pause, _x.max_update_rate, _x.gravity.x, _x.gravity.y, _x.gravity.z, _x.ode_config.auto_disable_bodies, _x.ode_config.sor_pgs_iters, _x.ode_config.sor_pgs_w, _x.ode_config.contact_surface_layer, _x.ode_config.contact_max_correcting_vel, _x.ode_config.cfm, _x.ode_config.erp, _x.ode_config.max_contacts,) = _struct_dB4dBI5dI.unpack(str[start:end]) 00152 self.pause = bool(self.pause) 00153 self.ode_config.auto_disable_bodies = bool(self.ode_config.auto_disable_bodies) 00154 return self 00155 except struct.error as e: 00156 raise roslib.message.DeserializationError(e) #most likely buffer underfill 00157 00158 _struct_I = roslib.message.struct_I 00159 _struct_dB4dBI5dI = struct.Struct("<dB4dBI5dI") 00160 """autogenerated by genmsg_py from SetPhysicsPropertiesResponse.msg. Do not edit.""" 00161 import roslib.message 00162 import struct 00163 00164 00165 class SetPhysicsPropertiesResponse(roslib.message.Message): 00166 _md5sum = "2ec6f3eff0161f4257b808b12bc830c2" 00167 _type = "gazebo/SetPhysicsPropertiesResponse" 00168 _has_header = False #flag to mark the presence of a Header object 00169 _full_text = """bool success 00170 string status_message 00171 00172 00173 """ 00174 __slots__ = ['success','status_message'] 00175 _slot_types = ['bool','string'] 00176 00177 def __init__(self, *args, **kwds): 00178 """ 00179 Constructor. Any message fields that are implicitly/explicitly 00180 set to None will be assigned a default value. The recommend 00181 use is keyword arguments as this is more robust to future message 00182 changes. You cannot mix in-order arguments and keyword arguments. 00183 00184 The available fields are: 00185 success,status_message 00186 00187 @param args: complete set of field values, in .msg order 00188 @param kwds: use keyword arguments corresponding to message field names 00189 to set specific fields. 00190 """ 00191 if args or kwds: 00192 super(SetPhysicsPropertiesResponse, self).__init__(*args, **kwds) 00193 #message fields cannot be None, assign default values for those that are 00194 if self.success is None: 00195 self.success = False 00196 if self.status_message is None: 00197 self.status_message = '' 00198 else: 00199 self.success = False 00200 self.status_message = '' 00201 00202 def _get_types(self): 00203 """ 00204 internal API method 00205 """ 00206 return self._slot_types 00207 00208 def serialize(self, buff): 00209 """ 00210 serialize message into buffer 00211 @param buff: buffer 00212 @type buff: StringIO 00213 """ 00214 try: 00215 buff.write(_struct_B.pack(self.success)) 00216 _x = self.status_message 00217 length = len(_x) 00218 buff.write(struct.pack('<I%ss'%length, length, _x)) 00219 except struct.error as se: self._check_types(se) 00220 except TypeError as te: self._check_types(te) 00221 00222 def deserialize(self, str): 00223 """ 00224 unpack serialized message in str into this message instance 00225 @param str: byte array of serialized message 00226 @type str: str 00227 """ 00228 try: 00229 end = 0 00230 start = end 00231 end += 1 00232 (self.success,) = _struct_B.unpack(str[start:end]) 00233 self.success = bool(self.success) 00234 start = end 00235 end += 4 00236 (length,) = _struct_I.unpack(str[start:end]) 00237 start = end 00238 end += length 00239 self.status_message = str[start:end] 00240 return self 00241 except struct.error as e: 00242 raise roslib.message.DeserializationError(e) #most likely buffer underfill 00243 00244 00245 def serialize_numpy(self, buff, numpy): 00246 """ 00247 serialize message with numpy array types into buffer 00248 @param buff: buffer 00249 @type buff: StringIO 00250 @param numpy: numpy python module 00251 @type numpy module 00252 """ 00253 try: 00254 buff.write(_struct_B.pack(self.success)) 00255 _x = self.status_message 00256 length = len(_x) 00257 buff.write(struct.pack('<I%ss'%length, length, _x)) 00258 except struct.error as se: self._check_types(se) 00259 except TypeError as te: self._check_types(te) 00260 00261 def deserialize_numpy(self, str, numpy): 00262 """ 00263 unpack serialized message in str into this message instance using numpy for array types 00264 @param str: byte array of serialized message 00265 @type str: str 00266 @param numpy: numpy python module 00267 @type numpy: module 00268 """ 00269 try: 00270 end = 0 00271 start = end 00272 end += 1 00273 (self.success,) = _struct_B.unpack(str[start:end]) 00274 self.success = bool(self.success) 00275 start = end 00276 end += 4 00277 (length,) = _struct_I.unpack(str[start:end]) 00278 start = end 00279 end += length 00280 self.status_message = str[start:end] 00281 return self 00282 except struct.error as e: 00283 raise roslib.message.DeserializationError(e) #most likely buffer underfill 00284 00285 _struct_I = roslib.message.struct_I 00286 _struct_B = struct.Struct("<B") 00287 class SetPhysicsProperties(roslib.message.ServiceDefinition): 00288 _type = 'gazebo/SetPhysicsProperties' 00289 _md5sum = 'ada1e937aad7900f65e797d65aabb0c1' 00290 _request_class = SetPhysicsPropertiesRequest 00291 _response_class = SetPhysicsPropertiesResponse