door_msgs/Door Message

File: door_msgs/Door.msg

Header header
geometry_msgs/Point32 frame_p1  ## position of the door frame
geometry_msgs/Point32 frame_p2  ## position of the door frame
geometry_msgs/Point32 door_p1   ## Ground plane projection of a point on the plane of the door 
geometry_msgs/Point32 door_p2   ## Ground plane projection of a point on the plane of the door
geometry_msgs/Point32 handle    ## Position of the door handle
float32 height               ## Height of the door

int32 UNKNOWN=0

int32 HINGE_P1=1
int32 HINGE_P2=2
int32 hinge                  

int32 ROT_DIR_CLOCKWISE=1
int32 ROT_DIR_COUNTERCLOCKWISE=2
int32 rot_dir                

int32 LOCKED=1
int32 LATCHED=2
int32 UNLATCHED=3
int32 latch_state            

geometry_msgs/Vector3 travel_dir           ## vector pointing in the direction the robot is going to travel through the door
float32 weight               ## @Sachin: what do we use this for?



Expanded Definition

int32 UNKNOWN=0
int32 HINGE_P1=1
int32 HINGE_P2=2
int32 ROT_DIR_CLOCKWISE=1
int32 ROT_DIR_COUNTERCLOCKWISE=2
int32 LOCKED=1
int32 LATCHED=2
int32 UNLATCHED=3
Header header
    uint32 seq
    time stamp
    string frame_id
geometry_msgs/Point32 frame_p1
    float32 x
    float32 y
    float32 z
geometry_msgs/Point32 frame_p2
    float32 x
    float32 y
    float32 z
geometry_msgs/Point32 door_p1
    float32 x
    float32 y
    float32 z
geometry_msgs/Point32 door_p2
    float32 x
    float32 y
    float32 z
geometry_msgs/Point32 handle
    float32 x
    float32 y
    float32 z
float32 height
int32 hinge
int32 rot_dir
int32 latch_state
geometry_msgs/Vector3 travel_dir
    float64 x
    float64 y
    float64 z
float32 weight