-
Notifications
You must be signed in to change notification settings - Fork 0
/
Copy pathConstants.js
148 lines (136 loc) · 5.95 KB
/
Constants.js
1
2
3
4
5
6
7
8
9
10
11
12
13
14
15
16
17
18
19
20
21
22
23
24
25
26
27
28
29
30
31
32
33
34
35
36
37
38
39
40
41
42
43
44
45
46
47
48
49
50
51
52
53
54
55
56
57
58
59
60
61
62
63
64
65
66
67
68
69
70
71
72
73
74
75
76
77
78
79
80
81
82
83
84
85
86
87
88
89
90
91
92
93
94
95
96
97
98
99
100
101
102
103
104
105
106
107
108
109
110
111
112
113
114
115
116
117
118
119
120
121
122
123
124
125
126
127
128
129
130
131
132
133
134
135
136
137
138
139
140
141
142
143
144
145
146
147
148
import { MEAL_STATE } from './GlobalState'
// How often to check if ROS is connected
export const ROS_CHECK_INTERVAL_MS = 1000
// The RealSense's default video stream is 640x480
export const REALSENSE_WIDTH = 640
export const REALSENSE_HEIGHT = 480
/**
* If the app has not transitioned states in this amount of time, it will reset
* to PreMeal on the next rendering.
*/
export const TIME_TO_RESET_MS = 3600000 // 1 hour in milliseconds
/**
* A dictionary containing the icon associated with each "robot moving" state
* except the Bite Acquisition state which has only a back button in footer.
* This dictionary is used to populate buttons with the icon images for states
* that those buttons will transition to.
* The keys are the meal states where the robot moves.
* Each key is paired with a value of an svg icon image of that meal state.
*/
let MOVING_STATE_ICON_DICT = {}
MOVING_STATE_ICON_DICT[MEAL_STATE.R_MovingAbovePlate] = '/robot_state_imgs/move_above_plate_position.svg'
MOVING_STATE_ICON_DICT[MEAL_STATE.R_MovingToRestingPosition] = '/robot_state_imgs/move_to_resting_position.svg'
MOVING_STATE_ICON_DICT[MEAL_STATE.R_MovingToStagingConfiguration] = '/robot_state_imgs/move_to_staging_configuration.svg'
MOVING_STATE_ICON_DICT[MEAL_STATE.R_MovingFromMouth] = '/robot_state_imgs/move_to_staging_configuration.svg'
MOVING_STATE_ICON_DICT[MEAL_STATE.R_MovingToMouth] = '/robot_state_imgs/move_to_mouth_position.svg'
MOVING_STATE_ICON_DICT[MEAL_STATE.R_StowingArm] = '/robot_state_imgs/stowing_arm_position.svg'
export { MOVING_STATE_ICON_DICT }
/**
* A set containing the states where the robot does not move.
*
* NOTE: Although in R_DetectingFace the robot does not technically move,
* the app might transition out of that state into a robot motion state without
* user intervention, so it is not included in this set.
*/
let NON_MOVING_STATES = new Set()
NON_MOVING_STATES.add(MEAL_STATE.U_PreMeal)
NON_MOVING_STATES.add(MEAL_STATE.U_BiteSelection)
NON_MOVING_STATES.add(MEAL_STATE.U_BiteAcquisitionCheck)
NON_MOVING_STATES.add(MEAL_STATE.U_BiteDone)
NON_MOVING_STATES.add(MEAL_STATE.U_PostMeal)
export { NON_MOVING_STATES }
// The names of the ROS topic(s)
export const CAMERA_FEED_TOPIC = '/local/camera/color/image_raw/compressed'
export const FACE_DETECTION_TOPIC = '/face_detection'
export const FACE_DETECTION_TOPIC_MSG = 'ada_feeding_msgs/FaceDetection'
export const FACE_DETECTION_IMG_TOPIC = '/face_detection_img/compressed'
export const ROBOT_COMPRESSED_IMG_TOPICS = [CAMERA_FEED_TOPIC, FACE_DETECTION_IMG_TOPIC]
// States from which, if they fail, it is NOT okay for the user to retry the
// same action.
let NON_RETRYABLE_STATES = new Set()
NON_RETRYABLE_STATES.add(MEAL_STATE.R_BiteAcquisition)
export { NON_RETRYABLE_STATES }
/**
* For states that call ROS actions, this dictionary contains
* the action name and the message type
*/
let ROS_ACTIONS_NAMES = {}
ROS_ACTIONS_NAMES[MEAL_STATE.R_MovingAbovePlate] = {
actionName: 'MoveAbovePlate',
messageType: 'ada_feeding_msgs/action/MoveTo'
}
ROS_ACTIONS_NAMES[MEAL_STATE.U_BiteSelection] = {
actionName: 'SegmentFromPoint',
messageType: 'ada_feeding_msgs/action/SegmentFromPoint'
}
ROS_ACTIONS_NAMES[MEAL_STATE.R_BiteAcquisition] = {
actionName: 'AcquireFood',
messageType: 'ada_feeding_msgs/action/AcquireFood'
}
ROS_ACTIONS_NAMES[MEAL_STATE.R_MovingToRestingPosition] = {
actionName: 'MoveToRestingPosition',
messageType: 'ada_feeding_msgs/action/MoveTo'
}
ROS_ACTIONS_NAMES[MEAL_STATE.R_MovingToStagingConfiguration] = {
actionName: 'MoveToStagingConfiguration',
messageType: 'ada_feeding_msgs/action/MoveTo'
}
ROS_ACTIONS_NAMES[MEAL_STATE.R_MovingFromMouth] = {
actionName: 'MoveFromMouth',
messageType: 'ada_feeding_msgs/action/MoveTo'
}
ROS_ACTIONS_NAMES[MEAL_STATE.R_MovingToMouth] = {
actionName: 'MoveToMouth',
messageType: 'ada_feeding_msgs/action/MoveToMouth'
}
ROS_ACTIONS_NAMES[MEAL_STATE.R_StowingArm] = {
actionName: 'MoveToStowLocation',
messageType: 'ada_feeding_msgs/action/MoveTo'
}
export { ROS_ACTIONS_NAMES }
/**
* For states that call ROS services, this dictionary contains
* the service name and the message type
*/
let ROS_SERVICE_NAMES = {}
ROS_SERVICE_NAMES[MEAL_STATE.R_DetectingFace] = {
serviceName: 'toggle_face_detection',
messageType: 'std_srvs/srv/SetBool'
}
export { ROS_SERVICE_NAMES }
export const CLEAR_OCTOMAP_SERVICE_NAME = 'clear_octomap'
export const CLEAR_OCTOMAP_SERVICE_TYPE = 'std_srvs/srv/Empty'
export const ACQUISITION_REPORT_SERVICE_NAME = 'ada_feeding_action_select/action_report'
export const ACQUISITION_REPORT_SERVICE_TYPE = 'ada_feeding_msgs/srv/AcquisitionReport'
export const GET_PARAMETERS_SERVICE_NAME = 'ada_feeding_action_servers/get_parameters'
export const GET_PARAMETERS_SERVICE_TYPE = 'rcl_interfaces/srv/GetParameters'
export const SET_PARAMETERS_SERVICE_NAME = 'ada_feeding_action_servers/set_parameters'
export const SET_PARAMETERS_SERVICE_TYPE = 'rcl_interfaces/srv/SetParameters'
/**
* The meaning of the status that motion actions return in their results.
* These should match the action definition(s).
*/
export const MOTION_STATUS_SUCCESS = 0
export const MOTION_STATUS_PLANNING_FAILED = 1
export const MOTION_STATUS_MOTION_FAILED = 2
export const MOTION_STATUS_CANCELED = 3
export const MOTION_STATUS_UNKNOWN = 99
/**
* The meaning of the status that segmentation actions return in their results.
* These should match the action definition(s).
*/
export const SEGMENTATION_STATUS_SUCCESS = 0
export const SEGMENTATION_STATUS_FAILED = 1
export const SEGMENTATION_STATUS_CANCELED = 3
export const SEGMENTATION_STATUS_UNKNOWN = 99
/**
* The meaning of ROS Action statuses.
* https://github.com/ros2/rcl_interfaces/blob/humble/action_msgs/msg/GoalStatus.msg
*/
export const ROS_ACTION_STATUS_UNKNOWN = 0
export const ROS_ACTION_STATUS_ACCEPTED = 1
export const ROS_ACTION_STATUS_EXECUTING = 2
export const ROS_ACTION_STATUS_CANCELING = 3
export const ROS_ACTION_STATUS_SUCCEED = 4
export const ROS_ACTION_STATUS_CANCELED = 5
export const ROS_ACTION_STATUS_ABORT = 6