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