$search
00001 /* Auto-generated by genmsg_cpp for file /home/rosbuild/hudson/workspace/doc-electric-arm_navigation_experimental/doc_stacks/2013-03-01_14-08-43.137802/arm_navigation_experimental/head_monitor_msgs/msg/PreplanHeadScanGoal.msg */ 00002 #ifndef HEAD_MONITOR_MSGS_MESSAGE_PREPLANHEADSCANGOAL_H 00003 #define HEAD_MONITOR_MSGS_MESSAGE_PREPLANHEADSCANGOAL_H 00004 #include <string> 00005 #include <vector> 00006 #include <map> 00007 #include <ostream> 00008 #include "ros/serialization.h" 00009 #include "ros/builtin_message_traits.h" 00010 #include "ros/message_operations.h" 00011 #include "ros/time.h" 00012 00013 #include "ros/macros.h" 00014 00015 #include "ros/assert.h" 00016 00017 #include "arm_navigation_msgs/MotionPlanRequest.h" 00018 00019 namespace head_monitor_msgs 00020 { 00021 template <class ContainerAllocator> 00022 struct PreplanHeadScanGoal_ { 00023 typedef PreplanHeadScanGoal_<ContainerAllocator> Type; 00024 00025 PreplanHeadScanGoal_() 00026 : group_name() 00027 , head_monitor_link() 00028 , motion_plan_request() 00029 { 00030 } 00031 00032 PreplanHeadScanGoal_(const ContainerAllocator& _alloc) 00033 : group_name(_alloc) 00034 , head_monitor_link(_alloc) 00035 , motion_plan_request(_alloc) 00036 { 00037 } 00038 00039 typedef std::basic_string<char, std::char_traits<char>, typename ContainerAllocator::template rebind<char>::other > _group_name_type; 00040 std::basic_string<char, std::char_traits<char>, typename ContainerAllocator::template rebind<char>::other > group_name; 00041 00042 typedef std::basic_string<char, std::char_traits<char>, typename ContainerAllocator::template rebind<char>::other > _head_monitor_link_type; 00043 std::basic_string<char, std::char_traits<char>, typename ContainerAllocator::template rebind<char>::other > head_monitor_link; 00044 00045 typedef ::arm_navigation_msgs::MotionPlanRequest_<ContainerAllocator> _motion_plan_request_type; 00046 ::arm_navigation_msgs::MotionPlanRequest_<ContainerAllocator> motion_plan_request; 00047 00048 00049 private: 00050 static const char* __s_getDataType_() { return "head_monitor_msgs/PreplanHeadScanGoal"; } 00051 public: 00052 ROS_DEPRECATED static const std::string __s_getDataType() { return __s_getDataType_(); } 00053 00054 ROS_DEPRECATED const std::string __getDataType() const { return __s_getDataType_(); } 00055 00056 private: 00057 static const char* __s_getMD5Sum_() { return "565652fd52e32966cc5c599108653bf9"; } 00058 public: 00059 ROS_DEPRECATED static const std::string __s_getMD5Sum() { return __s_getMD5Sum_(); } 00060 00061 ROS_DEPRECATED const std::string __getMD5Sum() const { return __s_getMD5Sum_(); } 00062 00063 private: 00064 static const char* __s_getMessageDefinition_() { return "# ====== DO NOT MODIFY! AUTOGENERATED FROM AN ACTION DEFINITION ======\n\ 00065 # The motion plan request\n\ 00066 string group_name\n\ 00067 string head_monitor_link\n\ 00068 arm_navigation_msgs/MotionPlanRequest motion_plan_request\n\ 00069 \n\ 00070 ================================================================================\n\ 00071 MSG: arm_navigation_msgs/MotionPlanRequest\n\ 00072 # This service contains the definition for a request to the motion\n\ 00073 # planner and the output it provides\n\ 00074 \n\ 00075 # Parameters for the workspace that the planner should work inside\n\ 00076 arm_navigation_msgs/WorkspaceParameters workspace_parameters\n\ 00077 \n\ 00078 # Starting state updates. If certain joints should be considered\n\ 00079 # at positions other than the current ones, these positions should\n\ 00080 # be set here\n\ 00081 arm_navigation_msgs/RobotState start_state\n\ 00082 \n\ 00083 # The goal state for the model to plan for. The goal is achieved\n\ 00084 # if all constraints are satisfied\n\ 00085 arm_navigation_msgs/Constraints goal_constraints\n\ 00086 \n\ 00087 # No state at any point along the path in the produced motion plan will violate these constraints\n\ 00088 arm_navigation_msgs/Constraints path_constraints\n\ 00089 \n\ 00090 # The name of the motion planner to use. If no name is specified,\n\ 00091 # a default motion planner will be used\n\ 00092 string planner_id\n\ 00093 \n\ 00094 # The name of the group of joints on which this planner is operating\n\ 00095 string group_name\n\ 00096 \n\ 00097 # The number of times this plan is to be computed. Shortest solution\n\ 00098 # will be reported.\n\ 00099 int32 num_planning_attempts\n\ 00100 \n\ 00101 # The maximum amount of time the motion planner is allowed to plan for\n\ 00102 duration allowed_planning_time\n\ 00103 \n\ 00104 # An expected path duration (in seconds) along with an expected discretization of the path allows the planner to determine the discretization of the trajectory that it returns\n\ 00105 duration expected_path_duration\n\ 00106 duration expected_path_dt\n\ 00107 \n\ 00108 ================================================================================\n\ 00109 MSG: arm_navigation_msgs/WorkspaceParameters\n\ 00110 # This message contains a set of parameters useful in\n\ 00111 # setting up the workspace for planning\n\ 00112 arm_navigation_msgs/Shape workspace_region_shape\n\ 00113 geometry_msgs/PoseStamped workspace_region_pose\n\ 00114 \n\ 00115 \n\ 00116 ================================================================================\n\ 00117 MSG: arm_navigation_msgs/Shape\n\ 00118 byte SPHERE=0\n\ 00119 byte BOX=1\n\ 00120 byte CYLINDER=2\n\ 00121 byte MESH=3\n\ 00122 \n\ 00123 byte type\n\ 00124 \n\ 00125 \n\ 00126 #### define sphere, box, cylinder ####\n\ 00127 # the origin of each shape is considered at the shape's center\n\ 00128 \n\ 00129 # for sphere\n\ 00130 # radius := dimensions[0]\n\ 00131 \n\ 00132 # for cylinder\n\ 00133 # radius := dimensions[0]\n\ 00134 # length := dimensions[1]\n\ 00135 # the length is along the Z axis\n\ 00136 \n\ 00137 # for box\n\ 00138 # size_x := dimensions[0]\n\ 00139 # size_y := dimensions[1]\n\ 00140 # size_z := dimensions[2]\n\ 00141 float64[] dimensions\n\ 00142 \n\ 00143 \n\ 00144 #### define mesh ####\n\ 00145 \n\ 00146 # list of triangles; triangle k is defined by tre vertices located\n\ 00147 # at indices triangles[3k], triangles[3k+1], triangles[3k+2]\n\ 00148 int32[] triangles\n\ 00149 geometry_msgs/Point[] vertices\n\ 00150 \n\ 00151 ================================================================================\n\ 00152 MSG: geometry_msgs/Point\n\ 00153 # This contains the position of a point in free space\n\ 00154 float64 x\n\ 00155 float64 y\n\ 00156 float64 z\n\ 00157 \n\ 00158 ================================================================================\n\ 00159 MSG: geometry_msgs/PoseStamped\n\ 00160 # A Pose with reference coordinate frame and timestamp\n\ 00161 Header header\n\ 00162 Pose pose\n\ 00163 \n\ 00164 ================================================================================\n\ 00165 MSG: std_msgs/Header\n\ 00166 # Standard metadata for higher-level stamped data types.\n\ 00167 # This is generally used to communicate timestamped data \n\ 00168 # in a particular coordinate frame.\n\ 00169 # \n\ 00170 # sequence ID: consecutively increasing ID \n\ 00171 uint32 seq\n\ 00172 #Two-integer timestamp that is expressed as:\n\ 00173 # * stamp.secs: seconds (stamp_secs) since epoch\n\ 00174 # * stamp.nsecs: nanoseconds since stamp_secs\n\ 00175 # time-handling sugar is provided by the client library\n\ 00176 time stamp\n\ 00177 #Frame this data is associated with\n\ 00178 # 0: no frame\n\ 00179 # 1: global frame\n\ 00180 string frame_id\n\ 00181 \n\ 00182 ================================================================================\n\ 00183 MSG: geometry_msgs/Pose\n\ 00184 # A representation of pose in free space, composed of postion and orientation. \n\ 00185 Point position\n\ 00186 Quaternion orientation\n\ 00187 \n\ 00188 ================================================================================\n\ 00189 MSG: geometry_msgs/Quaternion\n\ 00190 # This represents an orientation in free space in quaternion form.\n\ 00191 \n\ 00192 float64 x\n\ 00193 float64 y\n\ 00194 float64 z\n\ 00195 float64 w\n\ 00196 \n\ 00197 ================================================================================\n\ 00198 MSG: arm_navigation_msgs/RobotState\n\ 00199 # This message contains information about the robot state, i.e. the positions of its joints and links\n\ 00200 sensor_msgs/JointState joint_state\n\ 00201 arm_navigation_msgs/MultiDOFJointState multi_dof_joint_state\n\ 00202 \n\ 00203 ================================================================================\n\ 00204 MSG: sensor_msgs/JointState\n\ 00205 # This is a message that holds data to describe the state of a set of torque controlled joints. \n\ 00206 #\n\ 00207 # The state of each joint (revolute or prismatic) is defined by:\n\ 00208 # * the position of the joint (rad or m),\n\ 00209 # * the velocity of the joint (rad/s or m/s) and \n\ 00210 # * the effort that is applied in the joint (Nm or N).\n\ 00211 #\n\ 00212 # Each joint is uniquely identified by its name\n\ 00213 # The header specifies the time at which the joint states were recorded. All the joint states\n\ 00214 # in one message have to be recorded at the same time.\n\ 00215 #\n\ 00216 # This message consists of a multiple arrays, one for each part of the joint state. \n\ 00217 # The goal is to make each of the fields optional. When e.g. your joints have no\n\ 00218 # effort associated with them, you can leave the effort array empty. \n\ 00219 #\n\ 00220 # All arrays in this message should have the same size, or be empty.\n\ 00221 # This is the only way to uniquely associate the joint name with the correct\n\ 00222 # states.\n\ 00223 \n\ 00224 \n\ 00225 Header header\n\ 00226 \n\ 00227 string[] name\n\ 00228 float64[] position\n\ 00229 float64[] velocity\n\ 00230 float64[] effort\n\ 00231 \n\ 00232 ================================================================================\n\ 00233 MSG: arm_navigation_msgs/MultiDOFJointState\n\ 00234 #A representation of a multi-dof joint state\n\ 00235 time stamp\n\ 00236 string[] joint_names\n\ 00237 string[] frame_ids\n\ 00238 string[] child_frame_ids\n\ 00239 geometry_msgs/Pose[] poses\n\ 00240 \n\ 00241 ================================================================================\n\ 00242 MSG: arm_navigation_msgs/Constraints\n\ 00243 # This message contains a list of motion planning constraints.\n\ 00244 \n\ 00245 arm_navigation_msgs/JointConstraint[] joint_constraints\n\ 00246 arm_navigation_msgs/PositionConstraint[] position_constraints\n\ 00247 arm_navigation_msgs/OrientationConstraint[] orientation_constraints\n\ 00248 arm_navigation_msgs/VisibilityConstraint[] visibility_constraints\n\ 00249 \n\ 00250 ================================================================================\n\ 00251 MSG: arm_navigation_msgs/JointConstraint\n\ 00252 # Constrain the position of a joint to be within a certain bound\n\ 00253 string joint_name\n\ 00254 \n\ 00255 # the bound to be achieved is [position - tolerance_below, position + tolerance_above]\n\ 00256 float64 position\n\ 00257 float64 tolerance_above\n\ 00258 float64 tolerance_below\n\ 00259 \n\ 00260 # A weighting factor for this constraint\n\ 00261 float64 weight\n\ 00262 ================================================================================\n\ 00263 MSG: arm_navigation_msgs/PositionConstraint\n\ 00264 # This message contains the definition of a position constraint.\n\ 00265 Header header\n\ 00266 \n\ 00267 # The robot link this constraint refers to\n\ 00268 string link_name\n\ 00269 \n\ 00270 # The offset (in the link frame) for the target point on the link we are planning for\n\ 00271 geometry_msgs/Point target_point_offset\n\ 00272 \n\ 00273 # The nominal/target position for the point we are planning for\n\ 00274 geometry_msgs/Point position\n\ 00275 \n\ 00276 # The shape of the bounded region that constrains the position of the end-effector\n\ 00277 # This region is always centered at the position defined above\n\ 00278 arm_navigation_msgs/Shape constraint_region_shape\n\ 00279 \n\ 00280 # The orientation of the bounded region that constrains the position of the end-effector. \n\ 00281 # This allows the specification of non-axis aligned constraints\n\ 00282 geometry_msgs/Quaternion constraint_region_orientation\n\ 00283 \n\ 00284 # Constraint weighting factor - a weight for this constraint\n\ 00285 float64 weight\n\ 00286 \n\ 00287 ================================================================================\n\ 00288 MSG: arm_navigation_msgs/OrientationConstraint\n\ 00289 # This message contains the definition of an orientation constraint.\n\ 00290 Header header\n\ 00291 \n\ 00292 # The robot link this constraint refers to\n\ 00293 string link_name\n\ 00294 \n\ 00295 # The type of the constraint\n\ 00296 int32 type\n\ 00297 int32 LINK_FRAME=0\n\ 00298 int32 HEADER_FRAME=1\n\ 00299 \n\ 00300 # The desired orientation of the robot link specified as a quaternion\n\ 00301 geometry_msgs/Quaternion orientation\n\ 00302 \n\ 00303 # optional RPY error tolerances specified if \n\ 00304 float64 absolute_roll_tolerance\n\ 00305 float64 absolute_pitch_tolerance\n\ 00306 float64 absolute_yaw_tolerance\n\ 00307 \n\ 00308 # Constraint weighting factor - a weight for this constraint\n\ 00309 float64 weight\n\ 00310 \n\ 00311 ================================================================================\n\ 00312 MSG: arm_navigation_msgs/VisibilityConstraint\n\ 00313 # This message contains the definition of a visibility constraint.\n\ 00314 Header header\n\ 00315 \n\ 00316 # The point stamped target that needs to be kept within view of the sensor\n\ 00317 geometry_msgs/PointStamped target\n\ 00318 \n\ 00319 # The local pose of the frame in which visibility is to be maintained\n\ 00320 # The frame id should represent the robot link to which the sensor is attached\n\ 00321 # The visual axis of the sensor is assumed to be along the X axis of this frame\n\ 00322 geometry_msgs/PoseStamped sensor_pose\n\ 00323 \n\ 00324 # The deviation (in radians) that will be tolerated\n\ 00325 # Constraint error will be measured as the solid angle between the \n\ 00326 # X axis of the frame defined above and the vector between the origin \n\ 00327 # of the frame defined above and the target location\n\ 00328 float64 absolute_tolerance\n\ 00329 \n\ 00330 \n\ 00331 ================================================================================\n\ 00332 MSG: geometry_msgs/PointStamped\n\ 00333 # This represents a Point with reference coordinate frame and timestamp\n\ 00334 Header header\n\ 00335 Point point\n\ 00336 \n\ 00337 "; } 00338 public: 00339 ROS_DEPRECATED static const std::string __s_getMessageDefinition() { return __s_getMessageDefinition_(); } 00340 00341 ROS_DEPRECATED const std::string __getMessageDefinition() const { return __s_getMessageDefinition_(); } 00342 00343 ROS_DEPRECATED virtual uint8_t *serialize(uint8_t *write_ptr, uint32_t seq) const 00344 { 00345 ros::serialization::OStream stream(write_ptr, 1000000000); 00346 ros::serialization::serialize(stream, group_name); 00347 ros::serialization::serialize(stream, head_monitor_link); 00348 ros::serialization::serialize(stream, motion_plan_request); 00349 return stream.getData(); 00350 } 00351 00352 ROS_DEPRECATED virtual uint8_t *deserialize(uint8_t *read_ptr) 00353 { 00354 ros::serialization::IStream stream(read_ptr, 1000000000); 00355 ros::serialization::deserialize(stream, group_name); 00356 ros::serialization::deserialize(stream, head_monitor_link); 00357 ros::serialization::deserialize(stream, motion_plan_request); 00358 return stream.getData(); 00359 } 00360 00361 ROS_DEPRECATED virtual uint32_t serializationLength() const 00362 { 00363 uint32_t size = 0; 00364 size += ros::serialization::serializationLength(group_name); 00365 size += ros::serialization::serializationLength(head_monitor_link); 00366 size += ros::serialization::serializationLength(motion_plan_request); 00367 return size; 00368 } 00369 00370 typedef boost::shared_ptr< ::head_monitor_msgs::PreplanHeadScanGoal_<ContainerAllocator> > Ptr; 00371 typedef boost::shared_ptr< ::head_monitor_msgs::PreplanHeadScanGoal_<ContainerAllocator> const> ConstPtr; 00372 boost::shared_ptr<std::map<std::string, std::string> > __connection_header; 00373 }; // struct PreplanHeadScanGoal 00374 typedef ::head_monitor_msgs::PreplanHeadScanGoal_<std::allocator<void> > PreplanHeadScanGoal; 00375 00376 typedef boost::shared_ptr< ::head_monitor_msgs::PreplanHeadScanGoal> PreplanHeadScanGoalPtr; 00377 typedef boost::shared_ptr< ::head_monitor_msgs::PreplanHeadScanGoal const> PreplanHeadScanGoalConstPtr; 00378 00379 00380 template<typename ContainerAllocator> 00381 std::ostream& operator<<(std::ostream& s, const ::head_monitor_msgs::PreplanHeadScanGoal_<ContainerAllocator> & v) 00382 { 00383 ros::message_operations::Printer< ::head_monitor_msgs::PreplanHeadScanGoal_<ContainerAllocator> >::stream(s, "", v); 00384 return s;} 00385 00386 } // namespace head_monitor_msgs 00387 00388 namespace ros 00389 { 00390 namespace message_traits 00391 { 00392 template<class ContainerAllocator> struct IsMessage< ::head_monitor_msgs::PreplanHeadScanGoal_<ContainerAllocator> > : public TrueType {}; 00393 template<class ContainerAllocator> struct IsMessage< ::head_monitor_msgs::PreplanHeadScanGoal_<ContainerAllocator> const> : public TrueType {}; 00394 template<class ContainerAllocator> 00395 struct MD5Sum< ::head_monitor_msgs::PreplanHeadScanGoal_<ContainerAllocator> > { 00396 static const char* value() 00397 { 00398 return "565652fd52e32966cc5c599108653bf9"; 00399 } 00400 00401 static const char* value(const ::head_monitor_msgs::PreplanHeadScanGoal_<ContainerAllocator> &) { return value(); } 00402 static const uint64_t static_value1 = 0x565652fd52e32966ULL; 00403 static const uint64_t static_value2 = 0xcc5c599108653bf9ULL; 00404 }; 00405 00406 template<class ContainerAllocator> 00407 struct DataType< ::head_monitor_msgs::PreplanHeadScanGoal_<ContainerAllocator> > { 00408 static const char* value() 00409 { 00410 return "head_monitor_msgs/PreplanHeadScanGoal"; 00411 } 00412 00413 static const char* value(const ::head_monitor_msgs::PreplanHeadScanGoal_<ContainerAllocator> &) { return value(); } 00414 }; 00415 00416 template<class ContainerAllocator> 00417 struct Definition< ::head_monitor_msgs::PreplanHeadScanGoal_<ContainerAllocator> > { 00418 static const char* value() 00419 { 00420 return "# ====== DO NOT MODIFY! AUTOGENERATED FROM AN ACTION DEFINITION ======\n\ 00421 # The motion plan request\n\ 00422 string group_name\n\ 00423 string head_monitor_link\n\ 00424 arm_navigation_msgs/MotionPlanRequest motion_plan_request\n\ 00425 \n\ 00426 ================================================================================\n\ 00427 MSG: arm_navigation_msgs/MotionPlanRequest\n\ 00428 # This service contains the definition for a request to the motion\n\ 00429 # planner and the output it provides\n\ 00430 \n\ 00431 # Parameters for the workspace that the planner should work inside\n\ 00432 arm_navigation_msgs/WorkspaceParameters workspace_parameters\n\ 00433 \n\ 00434 # Starting state updates. If certain joints should be considered\n\ 00435 # at positions other than the current ones, these positions should\n\ 00436 # be set here\n\ 00437 arm_navigation_msgs/RobotState start_state\n\ 00438 \n\ 00439 # The goal state for the model to plan for. The goal is achieved\n\ 00440 # if all constraints are satisfied\n\ 00441 arm_navigation_msgs/Constraints goal_constraints\n\ 00442 \n\ 00443 # No state at any point along the path in the produced motion plan will violate these constraints\n\ 00444 arm_navigation_msgs/Constraints path_constraints\n\ 00445 \n\ 00446 # The name of the motion planner to use. If no name is specified,\n\ 00447 # a default motion planner will be used\n\ 00448 string planner_id\n\ 00449 \n\ 00450 # The name of the group of joints on which this planner is operating\n\ 00451 string group_name\n\ 00452 \n\ 00453 # The number of times this plan is to be computed. Shortest solution\n\ 00454 # will be reported.\n\ 00455 int32 num_planning_attempts\n\ 00456 \n\ 00457 # The maximum amount of time the motion planner is allowed to plan for\n\ 00458 duration allowed_planning_time\n\ 00459 \n\ 00460 # An expected path duration (in seconds) along with an expected discretization of the path allows the planner to determine the discretization of the trajectory that it returns\n\ 00461 duration expected_path_duration\n\ 00462 duration expected_path_dt\n\ 00463 \n\ 00464 ================================================================================\n\ 00465 MSG: arm_navigation_msgs/WorkspaceParameters\n\ 00466 # This message contains a set of parameters useful in\n\ 00467 # setting up the workspace for planning\n\ 00468 arm_navigation_msgs/Shape workspace_region_shape\n\ 00469 geometry_msgs/PoseStamped workspace_region_pose\n\ 00470 \n\ 00471 \n\ 00472 ================================================================================\n\ 00473 MSG: arm_navigation_msgs/Shape\n\ 00474 byte SPHERE=0\n\ 00475 byte BOX=1\n\ 00476 byte CYLINDER=2\n\ 00477 byte MESH=3\n\ 00478 \n\ 00479 byte type\n\ 00480 \n\ 00481 \n\ 00482 #### define sphere, box, cylinder ####\n\ 00483 # the origin of each shape is considered at the shape's center\n\ 00484 \n\ 00485 # for sphere\n\ 00486 # radius := dimensions[0]\n\ 00487 \n\ 00488 # for cylinder\n\ 00489 # radius := dimensions[0]\n\ 00490 # length := dimensions[1]\n\ 00491 # the length is along the Z axis\n\ 00492 \n\ 00493 # for box\n\ 00494 # size_x := dimensions[0]\n\ 00495 # size_y := dimensions[1]\n\ 00496 # size_z := dimensions[2]\n\ 00497 float64[] dimensions\n\ 00498 \n\ 00499 \n\ 00500 #### define mesh ####\n\ 00501 \n\ 00502 # list of triangles; triangle k is defined by tre vertices located\n\ 00503 # at indices triangles[3k], triangles[3k+1], triangles[3k+2]\n\ 00504 int32[] triangles\n\ 00505 geometry_msgs/Point[] vertices\n\ 00506 \n\ 00507 ================================================================================\n\ 00508 MSG: geometry_msgs/Point\n\ 00509 # This contains the position of a point in free space\n\ 00510 float64 x\n\ 00511 float64 y\n\ 00512 float64 z\n\ 00513 \n\ 00514 ================================================================================\n\ 00515 MSG: geometry_msgs/PoseStamped\n\ 00516 # A Pose with reference coordinate frame and timestamp\n\ 00517 Header header\n\ 00518 Pose pose\n\ 00519 \n\ 00520 ================================================================================\n\ 00521 MSG: std_msgs/Header\n\ 00522 # Standard metadata for higher-level stamped data types.\n\ 00523 # This is generally used to communicate timestamped data \n\ 00524 # in a particular coordinate frame.\n\ 00525 # \n\ 00526 # sequence ID: consecutively increasing ID \n\ 00527 uint32 seq\n\ 00528 #Two-integer timestamp that is expressed as:\n\ 00529 # * stamp.secs: seconds (stamp_secs) since epoch\n\ 00530 # * stamp.nsecs: nanoseconds since stamp_secs\n\ 00531 # time-handling sugar is provided by the client library\n\ 00532 time stamp\n\ 00533 #Frame this data is associated with\n\ 00534 # 0: no frame\n\ 00535 # 1: global frame\n\ 00536 string frame_id\n\ 00537 \n\ 00538 ================================================================================\n\ 00539 MSG: geometry_msgs/Pose\n\ 00540 # A representation of pose in free space, composed of postion and orientation. \n\ 00541 Point position\n\ 00542 Quaternion orientation\n\ 00543 \n\ 00544 ================================================================================\n\ 00545 MSG: geometry_msgs/Quaternion\n\ 00546 # This represents an orientation in free space in quaternion form.\n\ 00547 \n\ 00548 float64 x\n\ 00549 float64 y\n\ 00550 float64 z\n\ 00551 float64 w\n\ 00552 \n\ 00553 ================================================================================\n\ 00554 MSG: arm_navigation_msgs/RobotState\n\ 00555 # This message contains information about the robot state, i.e. the positions of its joints and links\n\ 00556 sensor_msgs/JointState joint_state\n\ 00557 arm_navigation_msgs/MultiDOFJointState multi_dof_joint_state\n\ 00558 \n\ 00559 ================================================================================\n\ 00560 MSG: sensor_msgs/JointState\n\ 00561 # This is a message that holds data to describe the state of a set of torque controlled joints. \n\ 00562 #\n\ 00563 # The state of each joint (revolute or prismatic) is defined by:\n\ 00564 # * the position of the joint (rad or m),\n\ 00565 # * the velocity of the joint (rad/s or m/s) and \n\ 00566 # * the effort that is applied in the joint (Nm or N).\n\ 00567 #\n\ 00568 # Each joint is uniquely identified by its name\n\ 00569 # The header specifies the time at which the joint states were recorded. All the joint states\n\ 00570 # in one message have to be recorded at the same time.\n\ 00571 #\n\ 00572 # This message consists of a multiple arrays, one for each part of the joint state. \n\ 00573 # The goal is to make each of the fields optional. When e.g. your joints have no\n\ 00574 # effort associated with them, you can leave the effort array empty. \n\ 00575 #\n\ 00576 # All arrays in this message should have the same size, or be empty.\n\ 00577 # This is the only way to uniquely associate the joint name with the correct\n\ 00578 # states.\n\ 00579 \n\ 00580 \n\ 00581 Header header\n\ 00582 \n\ 00583 string[] name\n\ 00584 float64[] position\n\ 00585 float64[] velocity\n\ 00586 float64[] effort\n\ 00587 \n\ 00588 ================================================================================\n\ 00589 MSG: arm_navigation_msgs/MultiDOFJointState\n\ 00590 #A representation of a multi-dof joint state\n\ 00591 time stamp\n\ 00592 string[] joint_names\n\ 00593 string[] frame_ids\n\ 00594 string[] child_frame_ids\n\ 00595 geometry_msgs/Pose[] poses\n\ 00596 \n\ 00597 ================================================================================\n\ 00598 MSG: arm_navigation_msgs/Constraints\n\ 00599 # This message contains a list of motion planning constraints.\n\ 00600 \n\ 00601 arm_navigation_msgs/JointConstraint[] joint_constraints\n\ 00602 arm_navigation_msgs/PositionConstraint[] position_constraints\n\ 00603 arm_navigation_msgs/OrientationConstraint[] orientation_constraints\n\ 00604 arm_navigation_msgs/VisibilityConstraint[] visibility_constraints\n\ 00605 \n\ 00606 ================================================================================\n\ 00607 MSG: arm_navigation_msgs/JointConstraint\n\ 00608 # Constrain the position of a joint to be within a certain bound\n\ 00609 string joint_name\n\ 00610 \n\ 00611 # the bound to be achieved is [position - tolerance_below, position + tolerance_above]\n\ 00612 float64 position\n\ 00613 float64 tolerance_above\n\ 00614 float64 tolerance_below\n\ 00615 \n\ 00616 # A weighting factor for this constraint\n\ 00617 float64 weight\n\ 00618 ================================================================================\n\ 00619 MSG: arm_navigation_msgs/PositionConstraint\n\ 00620 # This message contains the definition of a position constraint.\n\ 00621 Header header\n\ 00622 \n\ 00623 # The robot link this constraint refers to\n\ 00624 string link_name\n\ 00625 \n\ 00626 # The offset (in the link frame) for the target point on the link we are planning for\n\ 00627 geometry_msgs/Point target_point_offset\n\ 00628 \n\ 00629 # The nominal/target position for the point we are planning for\n\ 00630 geometry_msgs/Point position\n\ 00631 \n\ 00632 # The shape of the bounded region that constrains the position of the end-effector\n\ 00633 # This region is always centered at the position defined above\n\ 00634 arm_navigation_msgs/Shape constraint_region_shape\n\ 00635 \n\ 00636 # The orientation of the bounded region that constrains the position of the end-effector. \n\ 00637 # This allows the specification of non-axis aligned constraints\n\ 00638 geometry_msgs/Quaternion constraint_region_orientation\n\ 00639 \n\ 00640 # Constraint weighting factor - a weight for this constraint\n\ 00641 float64 weight\n\ 00642 \n\ 00643 ================================================================================\n\ 00644 MSG: arm_navigation_msgs/OrientationConstraint\n\ 00645 # This message contains the definition of an orientation constraint.\n\ 00646 Header header\n\ 00647 \n\ 00648 # The robot link this constraint refers to\n\ 00649 string link_name\n\ 00650 \n\ 00651 # The type of the constraint\n\ 00652 int32 type\n\ 00653 int32 LINK_FRAME=0\n\ 00654 int32 HEADER_FRAME=1\n\ 00655 \n\ 00656 # The desired orientation of the robot link specified as a quaternion\n\ 00657 geometry_msgs/Quaternion orientation\n\ 00658 \n\ 00659 # optional RPY error tolerances specified if \n\ 00660 float64 absolute_roll_tolerance\n\ 00661 float64 absolute_pitch_tolerance\n\ 00662 float64 absolute_yaw_tolerance\n\ 00663 \n\ 00664 # Constraint weighting factor - a weight for this constraint\n\ 00665 float64 weight\n\ 00666 \n\ 00667 ================================================================================\n\ 00668 MSG: arm_navigation_msgs/VisibilityConstraint\n\ 00669 # This message contains the definition of a visibility constraint.\n\ 00670 Header header\n\ 00671 \n\ 00672 # The point stamped target that needs to be kept within view of the sensor\n\ 00673 geometry_msgs/PointStamped target\n\ 00674 \n\ 00675 # The local pose of the frame in which visibility is to be maintained\n\ 00676 # The frame id should represent the robot link to which the sensor is attached\n\ 00677 # The visual axis of the sensor is assumed to be along the X axis of this frame\n\ 00678 geometry_msgs/PoseStamped sensor_pose\n\ 00679 \n\ 00680 # The deviation (in radians) that will be tolerated\n\ 00681 # Constraint error will be measured as the solid angle between the \n\ 00682 # X axis of the frame defined above and the vector between the origin \n\ 00683 # of the frame defined above and the target location\n\ 00684 float64 absolute_tolerance\n\ 00685 \n\ 00686 \n\ 00687 ================================================================================\n\ 00688 MSG: geometry_msgs/PointStamped\n\ 00689 # This represents a Point with reference coordinate frame and timestamp\n\ 00690 Header header\n\ 00691 Point point\n\ 00692 \n\ 00693 "; 00694 } 00695 00696 static const char* value(const ::head_monitor_msgs::PreplanHeadScanGoal_<ContainerAllocator> &) { return value(); } 00697 }; 00698 00699 } // namespace message_traits 00700 } // namespace ros 00701 00702 namespace ros 00703 { 00704 namespace serialization 00705 { 00706 00707 template<class ContainerAllocator> struct Serializer< ::head_monitor_msgs::PreplanHeadScanGoal_<ContainerAllocator> > 00708 { 00709 template<typename Stream, typename T> inline static void allInOne(Stream& stream, T m) 00710 { 00711 stream.next(m.group_name); 00712 stream.next(m.head_monitor_link); 00713 stream.next(m.motion_plan_request); 00714 } 00715 00716 ROS_DECLARE_ALLINONE_SERIALIZER; 00717 }; // struct PreplanHeadScanGoal_ 00718 } // namespace serialization 00719 } // namespace ros 00720 00721 namespace ros 00722 { 00723 namespace message_operations 00724 { 00725 00726 template<class ContainerAllocator> 00727 struct Printer< ::head_monitor_msgs::PreplanHeadScanGoal_<ContainerAllocator> > 00728 { 00729 template<typename Stream> static void stream(Stream& s, const std::string& indent, const ::head_monitor_msgs::PreplanHeadScanGoal_<ContainerAllocator> & v) 00730 { 00731 s << indent << "group_name: "; 00732 Printer<std::basic_string<char, std::char_traits<char>, typename ContainerAllocator::template rebind<char>::other > >::stream(s, indent + " ", v.group_name); 00733 s << indent << "head_monitor_link: "; 00734 Printer<std::basic_string<char, std::char_traits<char>, typename ContainerAllocator::template rebind<char>::other > >::stream(s, indent + " ", v.head_monitor_link); 00735 s << indent << "motion_plan_request: "; 00736 s << std::endl; 00737 Printer< ::arm_navigation_msgs::MotionPlanRequest_<ContainerAllocator> >::stream(s, indent + " ", v.motion_plan_request); 00738 } 00739 }; 00740 00741 00742 } // namespace message_operations 00743 } // namespace ros 00744 00745 #endif // HEAD_MONITOR_MSGS_MESSAGE_PREPLANHEADSCANGOAL_H 00746