-
Notifications
You must be signed in to change notification settings - Fork 45
New issue
Have a question about this project? Sign up for a free GitHub account to open an issue and contact its maintainers and the community.
By clicking “Sign up for GitHub”, you agree to our terms of service and privacy statement. We’ll occasionally send you account related emails.
Already on GitHub? Sign in to your account
Calibrate Unit D Multisense, add automatic general setup to drc_environment.sh #95
Changes from all commits
0fc4e29
50bc0db
a40489f
cff3caa
29ec451
42ce53a
fbba639
5ff2f41
fe2af77
46022e4
bd116c2
fd42200
e630bbf
324f92d
64030bf
8043908
c5e49db
File filter
Filter by extension
Conversations
Jump to
Diff view
Diff view
There are no files selected for viewing
Original file line number | Diff line number | Diff line change |
---|---|---|
|
@@ -82,7 +82,7 @@ setup_drc() | |
export ATLAS_ROBOT_INTERFACE=$DRC_BASE/software/atlas-collection/atlas/AtlasRobotInterface_3.3.0 | ||
} | ||
|
||
setup_robot_computers() | ||
setup_atlas_computers() | ||
{ | ||
# field computer | ||
if [ "paladin-12" = $(hostname) ] | ||
|
@@ -114,6 +114,29 @@ setup_robot_computers() | |
fi | ||
} | ||
|
||
setup_valkyrie_computers() | ||
{ | ||
# Edinburgh operator workstations | ||
if [ "angmar" = $(hostname) ] || [ "gondolin" = $(hostname) ] || [ "vis04" = $(hostname) ]; then | ||
There was a problem hiding this comment. Choose a reason for hiding this commentThe reason will be displayed to describe this comment to others. Learn more. who is vis04? There was a problem hiding this comment. Choose a reason for hiding this commentThe reason will be displayed to describe this comment to others. Learn more. From what I've seen, Kody must have renamed the operator workstation to vis04 since this is what shows up on the terminal ($edbot@vis04). I'd take one of the other two of the list but am unsure which one is the video capture station and which one the workstation computer. |
||
echo "Setting up Valkyrie Unit D for Edinburgh" | ||
export VAL_LINK_IP=10.185.0.40 | ||
export VAL_ZELDA_IP=10.185.0.41 | ||
export VAL_MULTISENSE_IP=10.185.0.42 | ||
export VAL_UNIT=D | ||
export LCM_DEFAULT_URL="udpm://239.255.76.76:7676?ttl=1" | ||
fi | ||
|
||
# MIT Valkyrie Workstations | ||
# TODO: MIT Valkyrie workstations | ||
if [ "vis03" = $(hostname) ]; then | ||
echo "Setting up Valkyrie Unit C for MIT" | ||
export VAL_LINK_IP=10.185.0.30 | ||
export VAL_ZELDA_IP=10.185.0.31 | ||
export VAL_MULTISENSE_IP=10.185.0.32 | ||
export VAL_UNIT=C | ||
fi | ||
} | ||
|
||
setup_network_sim() | ||
{ | ||
export LCM_URL_DRC_ROBOT="udpm://239.255.76.68:7668?ttl=0" | ||
|
@@ -159,8 +182,10 @@ set_drc_base | |
setup_drc | ||
setup_network_sim | ||
setup_lcm_communities | ||
setup_robot_computers | ||
setup_atlas_computers | ||
setup_valkyrie_computers | ||
|
||
# aliases | ||
alias cddrc='cd $DRC_BASE/software' | ||
alias rundrc='bot-procman-sheriff -l $DRC_BASE/software/config/atlas/robot.pmd' | ||
alias runval='bot-procman-sheriff -l $DRC_BASE/software/config/val/robot.pmd' |
Original file line number | Diff line number | Diff line change |
---|---|---|
@@ -0,0 +1,141 @@ | ||
# sensor head on unit D in Edinburgh | ||
|
||
coordinate_frames { | ||
|
||
################## Sensor Frames ################################### | ||
CAMERA_LEFT { | ||
# this cannot change - its rigid | ||
relative_to = "head"; | ||
history = 1000; | ||
update_channel = "HEAD_TO_LEFT_CAMERA_OPTICAL_FRAME"; | ||
initial_transform{ | ||
# location of left camera: | ||
translation = [ 0.0, 0.035, -0.002]; | ||
rpy = [ -90.0, 0.0, -90.0]; | ||
} | ||
} | ||
|
||
CAMERA_RIGHT { | ||
relative_to = "CAMERA_LEFT"; | ||
history = 1000; | ||
update_channel = "CAMERA_LEFT_TO_CAMERA_RIGHT"; | ||
initial_transform{ | ||
translation = [ 0.070, 0.0, 0.0]; | ||
rpy = [ 0.0, 0.0, 0.0]; | ||
} | ||
} | ||
|
||
|
||
################## Path from Camera to Laser: #################################### | ||
PRE_SPINDLE { | ||
# rosrun tf tf_echo multisense/left_camera_optical_frame multisense/motor | ||
relative_to = "CAMERA_LEFT"; | ||
history = 5000; | ||
update_channel = "CAMERA_LEFT_TO_PRE_SPINDLE"; | ||
initial_transform{ | ||
translation = [0.044, -0.085, -0.013]; | ||
rpy = [0.721, -0.419, -29.660]; | ||
} | ||
} | ||
|
||
POST_SPINDLE { | ||
relative_to = "PRE_SPINDLE"; | ||
history = 5000; | ||
max_frequency = 100; | ||
update_channel = "PRE_SPINDLE_TO_POST_SPINDLE"; | ||
initial_transform{ | ||
# pure rotation transform | ||
translation = [ 0.0, 0.0, 0.0 ]; | ||
quat = [ 1,0,0,0 ]; | ||
} | ||
} | ||
|
||
SCAN { | ||
relative_to = "POST_SPINDLE"; | ||
history = 5000; | ||
update_channel = "POST_SPINDLE_TO_SCAN"; | ||
initial_transform{ | ||
# rosrun tf tf_echo multisense/spindle multisense/head_hokuyo_frame | ||
translation = [-0.001, 0.015, 0.000]; | ||
rpy = [47.496, -89.187, -137.493]; | ||
} | ||
} | ||
|
||
SCAN_FREE { | ||
relative_to = "SCAN"; | ||
history = 1000; | ||
update_channel = "SCAN_TO_SCAN_FREE"; | ||
initial_transform{ | ||
translation=[ 0.0 , 0.0 , 0.0 ]; | ||
rpy = [0.0 , 0.0 , 0.0 ]; | ||
} | ||
} | ||
|
||
} | ||
|
||
|
||
cameras { | ||
# fx fy skew cx cy | ||
CAMERA_LEFT { | ||
lcm_channel = "CAMERA_LEFT"; | ||
coord_frame = "CAMERA_LEFT"; | ||
intrinsic_cal{ | ||
width = 1024; | ||
height= 1024; | ||
distortion_model = "plumb-bob"; | ||
distortion_k = [0,0,0]; | ||
distortion_p = [0,0]; | ||
pinhole = [ 556.183166504, 556.183166504, 0, 512.0, 512.0 ]; | ||
} | ||
} | ||
|
||
CAMERA_RIGHT { | ||
lcm_channel = "CAMERA_RIGHT"; | ||
coord_frame = "CAMERA_RIGHT"; | ||
intrinsic_cal{ | ||
width = 1024; | ||
height= 1024; | ||
distortion_model = "plumb-bob"; | ||
distortion_k = [0,0,0]; | ||
distortion_p = [0,0]; | ||
pinhole = [ 556.183166504, 556.183166504, 0, 512.0, 512.0 ]; | ||
} | ||
} | ||
|
||
CAMERA { | ||
lcm_channel = "CAMERA"; | ||
type = "stereo"; | ||
rotation = [1.0, 0.0, 0.0, 0.0, 1.0, 0.0, 0.0, 0.0, 1.0]; | ||
translation = [-0.0700, 0.0, 0.0]; | ||
} | ||
} | ||
|
||
|
||
planar_lidars { | ||
SCAN { | ||
viewer_color = [ 1.0, 0.0, 0.0 ]; # red | ||
max_range = 29.0; | ||
min_range = 0.1; | ||
frequency = 40; | ||
laser_type = "HOKUYO_UTM"; | ||
coord_frame = "SCAN"; | ||
lcm_channel = "SCAN"; | ||
surround_region = [0, 1000000]; | ||
up_region = [-1,-1]; | ||
down_region = [-1, -1]; | ||
max_range_free_dist = 29.0; | ||
} | ||
SCAN_FREE { | ||
viewer_color = [ 0.0, 0.0, 1.0 ]; # blue | ||
max_range = 29.0; | ||
min_range = 0.1; | ||
frequency = 40; | ||
laser_type = "HOKUYO_UTM"; | ||
coord_frame = "SCAN"; | ||
lcm_channel = "SCAN_FREE"; | ||
surround_region = [0, 1000000]; | ||
up_region = [-1,-1]; | ||
down_region = [-1, -1]; | ||
max_range_free_dist = 29.0; | ||
} | ||
} |
Original file line number | Diff line number | Diff line change |
---|---|---|
@@ -1,6 +1,6 @@ | ||
INCLUDE = [ | ||
"core_config.cfg", | ||
"multisense.cfg", | ||
"multisense_D_50.cfg", | ||
There was a problem hiding this comment. Choose a reason for hiding this commentThe reason will be displayed to describe this comment to others. Learn more. TODO: will need to have robot.cfg files co exist There was a problem hiding this comment. Choose a reason for hiding this commentThe reason will be displayed to describe this comment to others. Learn more. Opened #100 to track this to make this PR non-blocking. The ${VAL_UNIT} variable is probably a good approach for this, need to be incorporated in director then as well. Otherwise PR is ready to go |
||
"../atlas/common_components.cfg", | ||
"../atlas_sim_mit/control.cfg", | ||
"state_estimation.cfg" | ||
|
Original file line number | Diff line number | Diff line change |
---|---|---|
@@ -0,0 +1,7 @@ | ||
INCLUDE = [ | ||
"core_config.cfg", | ||
"multisense_C_xx.cfg", | ||
"../atlas/common_components.cfg", | ||
"../atlas_sim_mit/control.cfg", | ||
"state_estimation.cfg" | ||
]; |
There was a problem hiding this comment.
Choose a reason for hiding this comment
The reason will be displayed to describe this comment to others. Learn more.
setup_edinburgh_valkyrie_computers()
<<< I see now, no need to respond >>>