diff --git a/mobile_manipulator/emergency_pkg/CMakeLists.txt b/mobile_manipulator/emergency_pkg/CMakeLists.txt new file mode 100644 index 0000000..b6f6c03 --- /dev/null +++ b/mobile_manipulator/emergency_pkg/CMakeLists.txt @@ -0,0 +1,202 @@ +cmake_minimum_required(VERSION 3.0.2) +project(emergency_pkg) + +## Compile as C++11, supported in ROS Kinetic and newer +# add_compile_options(-std=c++11) + +## Find catkin macros and libraries +## if COMPONENTS list like find_package(catkin REQUIRED COMPONENTS xyz) +## is used, also find other catkin packages +find_package(catkin REQUIRED COMPONENTS + roscpp + sensor_msgs + std_msgs +) + +## System dependencies are found with CMake's conventions +# find_package(Boost REQUIRED COMPONENTS system) + + +## Uncomment this if the package has a setup.py. This macro ensures +## modules and global scripts declared therein get installed +## See http://ros.org/doc/api/catkin/html/user_guide/setup_dot_py.html +# catkin_python_setup() + +################################################ +## Declare ROS messages, services and actions ## +################################################ + +## To declare and build messages, services or actions from within this +## package, follow these steps: +## * Let MSG_DEP_SET be the set of packages whose message types you use in +## your messages/services/actions (e.g. std_msgs, actionlib_msgs, ...). +## * In the file package.xml: +## * add a build_depend tag for "message_generation" +## * add a build_depend and a exec_depend tag for each package in MSG_DEP_SET +## * If MSG_DEP_SET isn't empty the following dependency has been pulled in +## but can be declared for certainty nonetheless: +## * add a exec_depend tag for "message_runtime" +## * In this file (CMakeLists.txt): +## * add "message_generation" and every package in MSG_DEP_SET to +## find_package(catkin REQUIRED COMPONENTS ...) +## * add "message_runtime" and every package in MSG_DEP_SET to +## catkin_package(CATKIN_DEPENDS ...) +## * uncomment the add_*_files sections below as needed +## and list every .msg/.srv/.action file to be processed +## * uncomment the generate_messages entry below +## * add every package in MSG_DEP_SET to generate_messages(DEPENDENCIES ...) + +## Generate messages in the 'msg' folder +# add_message_files( +# FILES +# Message1.msg +# Message2.msg +# ) + +## Generate services in the 'srv' folder +# add_service_files( +# FILES +# Service1.srv +# Service2.srv +# ) + +## Generate actions in the 'action' folder +# add_action_files( +# FILES +# Action1.action +# Action2.action +# ) + +## Generate added messages and services with any dependencies listed here +# generate_messages( +# DEPENDENCIES +# sensor_msgs# std_msgs +# ) + +################################################ +## Declare ROS dynamic reconfigure parameters ## +################################################ + +## To declare and build dynamic reconfigure parameters within this +## package, follow these steps: +## * In the file package.xml: +## * add a build_depend and a exec_depend tag for "dynamic_reconfigure" +## * In this file (CMakeLists.txt): +## * add "dynamic_reconfigure" to +## find_package(catkin REQUIRED COMPONENTS ...) +## * uncomment the "generate_dynamic_reconfigure_options" section below +## and list every .cfg file to be processed + +## Generate dynamic reconfigure parameters in the 'cfg' folder +# generate_dynamic_reconfigure_options( +# cfg/DynReconf1.cfg +# cfg/DynReconf2.cfg +# ) + +################################### +## catkin specific configuration ## +################################### +## The catkin_package macro generates cmake config files for your package +## Declare things to be passed to dependent projects +## INCLUDE_DIRS: uncomment this if your package contains header files +## LIBRARIES: libraries you create in this project that dependent projects also need +## CATKIN_DEPENDS: catkin_packages dependent projects also need +## DEPENDS: system dependencies of this project that dependent projects also need +catkin_package( +# INCLUDE_DIRS include +# LIBRARIES emergency_pkg +# CATKIN_DEPENDS roscpp sensor_msgs std_msgs +# DEPENDS system_lib +) + +########### +## Build ## +########### + +## Specify additional locations of header files +## Your package locations should be listed before other locations +include_directories( +# include + ${catkin_INCLUDE_DIRS} +) + +## Declare a C++ library +# add_library(ir_emg_node src/ir_emg.cpp) + +## Add cmake target dependencies of the library +## as an example, code may need to be generated before libraries +## either from message generation or dynamic reconfigure +# add_dependencies(${PROJECT_NAME} ${${PROJECT_NAME}_EXPORTED_TARGETS} ${catkin_EXPORTED_TARGETS}) + +## Declare a C++ executable +## With catkin_make all packages are built within a single CMake context +## The recommended prefix ensures that target names across packages don't collide +add_executable(ir_emg_node src/ir_emg.cpp) + +## Rename C++ executable without prefix +## The above recommended prefix causes long target names, the following renames the +## target back to the shorter version for ease of user use +## e.g. "rosrun someones_pkg node" instead of "rosrun someones_pkg someones_pkg_node" +# set_target_properties(${PROJECT_NAME}_node PROPERTIES OUTPUT_NAME node PREFIX "") + +## Add cmake target dependencies of the executable +## same as for the library above +add_dependencies(ir_emg_node ${${PROJECT_NAME}_EXPORTED_TARGETS} ${catkin_EXPORTED_TARGETS}) + +## Specify libraries to link a library or executable target against +target_link_libraries(ir_emg_node ${catkin_LIBRARIES}) + +############# +## Install ## +############# + +# all install targets should use catkin DESTINATION variables +# See http://ros.org/doc/api/catkin/html/adv_user_guide/variables.html + +## Mark executable scripts (Python etc.) for installation +## in contrast to setup.py, you can choose the destination +# catkin_install_python(PROGRAMS +# scripts/my_python_script +# DESTINATION ${CATKIN_PACKAGE_BIN_DESTINATION} +# ) + +## Mark executables for installation +## See http://docs.ros.org/melodic/api/catkin/html/howto/format1/building_executables.html +# install(TARGETS ${PROJECT_NAME}_node +# RUNTIME DESTINATION ${CATKIN_PACKAGE_BIN_DESTINATION} +# ) + +## Mark libraries for installation +## See http://docs.ros.org/melodic/api/catkin/html/howto/format1/building_libraries.html +# install(TARGETS ${PROJECT_NAME} +# ARCHIVE DESTINATION ${CATKIN_PACKAGE_LIB_DESTINATION} +# LIBRARY DESTINATION ${CATKIN_PACKAGE_LIB_DESTINATION} +# RUNTIME DESTINATION ${CATKIN_GLOBAL_BIN_DESTINATION} +# ) + +## Mark cpp header files for installation +# install(DIRECTORY include/${PROJECT_NAME}/ +# DESTINATION ${CATKIN_PACKAGE_INCLUDE_DESTINATION} +# FILES_MATCHING PATTERN "*.h" +# PATTERN ".svn" EXCLUDE +# ) + +## Mark other files for installation (e.g. launch and bag files, etc.) +# install(FILES +# # myfile1 +# # myfile2 +# DESTINATION ${CATKIN_PACKAGE_SHARE_DESTINATION} +# ) + +############# +## Testing ## +############# + +## Add gtest based cpp test target and link libraries +# catkin_add_gtest(${PROJECT_NAME}-test test/test_emergency_pkg.cpp) +# if(TARGET ${PROJECT_NAME}-test) +# target_link_libraries(${PROJECT_NAME}-test ${PROJECT_NAME}) +# endif() + +## Add folders to be run by python nosetests +# catkin_add_nosetests(test) diff --git a/mobile_manipulator/emergency_pkg/package.xml b/mobile_manipulator/emergency_pkg/package.xml new file mode 100644 index 0000000..0fced19 --- /dev/null +++ b/mobile_manipulator/emergency_pkg/package.xml @@ -0,0 +1,68 @@ + + + emergency_pkg + 0.0.0 + The emergency_pkg package + + + + + didem-focal + + + + + + TODO + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + catkin + roscpp + sensor_msgs + std_msgs + roscpp + sensor_msgs + std_msgs + roscpp + sensor_msgs + std_msgs + + + + + + + + diff --git a/mobile_manipulator/emergency_pkg/scripts/emergency_publisher.py b/mobile_manipulator/emergency_pkg/scripts/emergency_publisher.py new file mode 100755 index 0000000..dc0c18a --- /dev/null +++ b/mobile_manipulator/emergency_pkg/scripts/emergency_publisher.py @@ -0,0 +1,41 @@ +#!/usr/bin/env python3 + +import numpy as np +import time + +import rospy +from std_msgs.msg import Int8, String + +class Emergency: + def __init__(self): + rospy.init_node("odom_combined") + # self.emg_publisher = rospy.Publisher("emg", Int8, queue_size=10) + self.light_curtain_publisher = rospy.Publisher("robot_rgb", String, queue_size=10) + # rospy.Subscriber("emg", Int8, self.emg_callback) + rospy.Subscriber("ui_emg", Int8, self.ui_emg_callback) + self.ui_emg = Int8() + self.ui_emg.data = 0 + self.main() + + def main(self): + rate = rospy.Rate(5) + while not rospy.is_shutdown(): + # self.emg_publisher.publish(self.ui_emg) + rate.sleep() + + def emg_callback(self, msg): + self.general_emg = msg.data + + def ui_emg_callback(self, msg): + self.ui_emg.data = msg.data + if self.ui_emg.data == 0: + self.light_curtain_publisher.publish("{\"ID\":44}") + +if __name__ == "__main__": + Emergency() + + + + + + diff --git a/mobile_manipulator/emergency_pkg/scripts/odom_combined.py b/mobile_manipulator/emergency_pkg/scripts/odom_combined.py new file mode 100755 index 0000000..32c4ec3 --- /dev/null +++ b/mobile_manipulator/emergency_pkg/scripts/odom_combined.py @@ -0,0 +1,174 @@ +#!/usr/bin/env python3 + +import numpy as np +import time + +import rospy +from sensor_msgs.msg import Range +from nav_msgs.msg import Odometry +from tf.transformations import euler_from_quaternion + +class Kalman: + def __init__(self): + rospy.init_node("odom_combined") + rospy.Subscriber("odom", Odometry, self.odom_callback) + rospy.Subscriber("ota_ir",Range, self.ir_callback) + self.ir_origin = 2.4988601207733154 + self.main() + + def main(self): + rate = rospy.Rate(5) + pre_time = time.time() + self.state = None + # Save the Initial States + vehicle_position_history = [[0,0]] + vehicle_velocity_history = [[0,0]] + measurement_history = [None] + estimated_error_history = [None] + self.ir_position = [0,0] + self.odom = [0,0,0,0,0] + #self.state = np.array([0,0,0,0]) + #self.covariance = np.diag(np.array([init_pos_std*init_pos_std, + # init_pos_std*init_pos_std, + # init_vel_std*init_vel_std, + # init_vel_std*init_vel_std])) + + # Setup the Model F Matrix + + # Set the Q Matrix + accel_std = 0.1 + + # Setup the Model H Matrix + self.H = np.array([[1,0,0,0],[0,1,0,0]]) + + # Set the R Matrix + meas_std = 10.0 + self.R = np.diag([meas_std*meas_std, meas_std*meas_std]) + + measurement_innovation_history = [None] + measurement_innovation_covariance_history = [None] + + while not rospy.is_shutdown(): + step = time.time() + dt = step - pre_time + print("delta_t",dt) + + # Create the Simulation Objects + + # Set Initial State and Covariance (COMMENT OUT FOR DELAYED INIT) + init_pos_std = 100 + init_vel_std = 100 + # KF Measurement + if self.ir_position != 0: + measurement = [self.ir_position[0],self.ir_position[1]] + + if self.state is not None and self.covariance is not None: + + # KF Prediction + # kalman_filter.prediction_step() + # Make Sure Filter is Initialised + x = self.state + P = self.covariance + H = self.H + R = self.R + self.Q = np.diag(np.array([(0.5*dt*dt),(0.5*dt*dt),dt,dt]) * (accel_std*accel_std)) + self.F = np.array([[1,0,dt,0], + [0,1,0,dt], + [0,0,1,0], + [0,0,0,1]]) + # Calculate Kalman Filter Prediction + x_predict = np.matmul(self.F, x) + P_predict = np.matmul(self.F, np.matmul(P, np.transpose(self.F))) + self.Q + + # Save Predicted State + self.state = x_predict + self.covariance = P_predict + + # kalman_filter.update_step(measurement) + + # Calculate Kalman Filter Update + z = np.array([measurement[0],measurement[1]]) # ir position + z_hat = np.matmul(H, x) + + y = z - z_hat + S = np.matmul(H,np.matmul(P,np.transpose(H))) + R + K = np.matmul(P,np.matmul(np.transpose(H),np.linalg.inv(S))) + + x_update = x + np.matmul(K, y) + P_update = np.matmul( (np.eye(4) - np.matmul(K,H)), P) + + print(x_update[0],x_update[1],x_update[2],x_update[3]) + + # Save Updated State + self.innovation = y + self.innovation_covariance = S + self.state = x_update + self.covariance = P_update + + measurement_innovation_history.append(self.innovation) + measurement_innovation_covariance_history.append(self.innovation_covariance) + + # Estimation Error + estimation_error = None + estimated_state = self.state + if estimated_state is not None: + estimation_error = [estimated_state[0] - measurement[0], + estimated_state[1] - measurement[1], + estimated_state[2] - self.odom[3], + estimated_state[3] - self.odom[4]] + + # Save Data + vehicle_position_history.append(measurement) + vehicle_velocity_history.append([self.odom[3],self.odom[4]]) + measurement_history.append(measurement) + estimated_error_history.append(estimation_error) + + # Calculate Stats + x_innov_std = np.std([v[0] for v in measurement_innovation_history if v is not None]) + y_innov_std = np.std([v[1] for v in measurement_innovation_history if v is not None]) + pos_mse = np.mean([(v[0]**2+v[1]**2) for v in estimated_error_history if v is not None]) + vel_mse = np.mean([(v[2]**2+v[3]**2) for v in estimated_error_history if v is not None]) + print('X Position Measurement Innovation Std: {} (m)'.format(x_innov_std)) + print('Y Position Measurement Innovation Std: {} (m)'.format(y_innov_std)) + print('Position Mean Squared Error: {} (m)^2'.format(pos_mse)) + print('Velocity Mean Squared Error: {} (m/s)^2'.format(vel_mse)) + + else: + self.state = np.array([measurement[0],measurement[1],0,0]) + # self.covariance = np.diag(np.array([self.R[0,0],self.R[1,1],init_vel_std*init_vel_std,init_vel_std*init_vel_std])) + self.covariance = np.diag(np.array([init_pos_std*init_pos_std, + init_pos_std*init_pos_std, + init_vel_std*init_vel_std, + init_vel_std*init_vel_std])) + print("else") + pre_time = step + rate.sleep() + + def odom_callback(self, msg): + position = msg.pose.pose.position + orientation = msg.pose.pose.orientation + _, _, yaw = euler_from_quaternion([orientation.x, + orientation.y, + orientation.z, + orientation.w]) + twist = msg.twist.twist + self.odom = [position.x, + position.y, + yaw, + twist.linear.x, + twist.angular.z] + # print(self.odom) + + def ir_callback(self, msg): + data = msg.range + self.ir_position[0] = self.ir_origin - data + self.ir_position[1] = 0 + +if __name__ == "__main__": + Kalman() + + + + + + diff --git a/mobile_manipulator/emergency_pkg/scripts/publisher_w_rate.py b/mobile_manipulator/emergency_pkg/scripts/publisher_w_rate.py new file mode 100755 index 0000000..1331119 --- /dev/null +++ b/mobile_manipulator/emergency_pkg/scripts/publisher_w_rate.py @@ -0,0 +1,57 @@ +#!/usr/bin/env python3 + +import numpy as np +import time + +import rospy +from std_msgs.msg import Int8, String +from nav_msgs.msg import Odometry +from geometry_msgs.msg import Twist + + +class RatePublisher: + def __init__(self): + rospy.init_node("odom_combined") + self.cmd_pub = rospy.Publisher("cmd_vel", Twist, queue_size=10) + self.robot_status = rospy.Publisher("mobile_status", String, queue_size=10) + rospy.Subscriber("cmd_vel", Twist, self.cmd_callback) + rospy.Subscriber("odom", Odometry, self.odom_callback) + rospy.Subscriber("emg", Int8, self.emg_callback) + + self.odom_x = 0 + self.vx = 0 + self.cmd_vx = 0 + self.emg_data = 0 + + self.main() + + def main(self): + rate = rospy.Rate(20) + while not rospy.is_shutdown(): + if abs(self.vx) > 0.01: + data = "Moving" + else: + data = "Idle" + + if self.odom_x > 2.10: + data = "Max_limit" + elif self.odom_x < 0.02: + data = "Min_limit" + + if self.emg_data: + data = "Alert" + self.robot_status.publish(data) + rate.sleep() + + def odom_callback(self, msg): + self.odom_x = msg.pose.pose.position.x + self.vx = msg.twist.twist.linear.x + + def emg_callback(self, msg): + self.emg_data = msg.data + + def cmd_callback(self, msg): + self.cmd_vx = msg.linear.x + +if __name__ == "__main__": + RobotStatus() diff --git a/mobile_manipulator/emergency_pkg/scripts/robot_status_publisher.py b/mobile_manipulator/emergency_pkg/scripts/robot_status_publisher.py new file mode 100755 index 0000000..851a19f --- /dev/null +++ b/mobile_manipulator/emergency_pkg/scripts/robot_status_publisher.py @@ -0,0 +1,57 @@ +#!/usr/bin/env python3 + +import numpy as np +import time + +import rospy +from std_msgs.msg import Int8, String +from nav_msgs.msg import Odometry +from geometry_msgs.msg import Twist + + +class RobotStatus: + def __init__(self): + rospy.init_node("odom_combined") + self.cmd_pub = rospy.Publisher("cmd_vel", Twist, queue_size=10) + self.robot_status = rospy.Publisher("mobile_status", String, queue_size=10) + rospy.Subscriber("cmd_vel", Twist, self.cmd_callback) + rospy.Subscriber("odom", Odometry, self.odom_callback) + rospy.Subscriber("emg", Int8, self.emg_callback) + + self.odom_x = 0 + self.vx = 0 + self.cmd_vx = 0 + self.emg_data = 0 + + self.main() + + def main(self): + rate = rospy.Rate(20) + while not rospy.is_shutdown(): + if abs(self.vx) > 0.01: + data = "Moving" + else: + data = "Idle" + + if self.odom_x > 2.08: + data = "Max_limit" + elif self.odom_x < 0.02: + data = "Min_limit" + + if self.emg_data: + data = "Alert" + self.robot_status.publish(data) + rate.sleep() + + def odom_callback(self, msg): + self.odom_x = msg.pose.pose.position.x + self.vx = msg.twist.twist.linear.x + + def emg_callback(self, msg): + self.emg_data = msg.data + + def cmd_callback(self, msg): + self.cmd_vx = msg.linear.x + +if __name__ == "__main__": + RobotStatus() diff --git a/mobile_manipulator/emergency_pkg/scripts/sendor_to_odom.py b/mobile_manipulator/emergency_pkg/scripts/sendor_to_odom.py new file mode 100755 index 0000000..e1e5419 --- /dev/null +++ b/mobile_manipulator/emergency_pkg/scripts/sendor_to_odom.py @@ -0,0 +1,73 @@ +#!/usr/bin/env python3 + +import numpy as np +import time +import json + +import rospy +from std_msgs.msg import String +from nav_msgs.msg import Odometry +from tf.transformations import euler_from_quaternion + +class SensorOdom: + def __init__(self): + rospy.init_node("odom_combined") + rospy.Subscriber("odom", Odometry, self.odom_callback) + rospy.Subscriber("low_laser", String, self.ir_callback) + self.ir_origin = 2.4988601207733154 + self.main() + + def main(self): + rate = rospy.Rate(5) + self.ir_position = None + self.odom = [0,0,0,0,0] + ir_vel = 0 + first_pose_flag = False + time_diff = 0 + + while not rospy.is_shutdown(): + if self.ir_position is not None: + if not first_pose_flag: + pre_pose = self.ir_position + pre_time = time.time() + first_pose_flag = True + pose_diff = self.ir_position - pre_pose + try: + ir_vel = pose_diff / (time.time() - pre_time) + print("vel",ir_vel, time.time() - pre_time) + except: + pass + pre_pose = self.ir_position + pre_time = time.time() + rate.sleep() + + def odom_callback(self, msg): + position = msg.pose.pose.position + orientation = msg.pose.pose.orientation + _, _, yaw = euler_from_quaternion([orientation.x, + orientation.y, + orientation.z, + orientation.w]) + twist = msg.twist.twist + self.odom = [position.x, + position.y, + yaw, + twist.linear.x, + twist.angular.z] + # print(self.odom) + + def ir_callback(self, msg): + data = json.loads(msg.data) + self.ir_position = float(data["Distance_MM"]) / 1000 + print("pose",self.ir_position) + + # self.ir_position = self.ir_origin - data + +if __name__ == "__main__": + SensorOdom() + + + + + + diff --git a/mobile_manipulator/emergency_pkg/src/ir_emg.cpp b/mobile_manipulator/emergency_pkg/src/ir_emg.cpp new file mode 100644 index 0000000..561f42d --- /dev/null +++ b/mobile_manipulator/emergency_pkg/src/ir_emg.cpp @@ -0,0 +1,88 @@ +#include +#include + +#include "ros/ros.h" +#include "sensor_msgs/Range.h" +#include "std_msgs/Bool.h" + + +std::vector ir_arr; +float min_ir; + +void irCallback(const sensor_msgs::Range::ConstPtr& msg) +{ + ir_arr.push_back(msg->range); +} +void ir1Callback(const sensor_msgs::Range::ConstPtr& msg) +{ + ir_arr.push_back(msg->range); +} +void ir2Callback(const sensor_msgs::Range::ConstPtr& msg) +{ + ir_arr.push_back(msg->range); +} +void ir3Callback(const sensor_msgs::Range::ConstPtr& msg) +{ + ir_arr.push_back(msg->range); +} +void ir4Callback(const sensor_msgs::Range::ConstPtr& msg) +{ + ir_arr.push_back(msg->range); +} +void ir5Callback(const sensor_msgs::Range::ConstPtr& msg) +{ + ir_arr.push_back(msg->range); +} +void ir6Callback(const sensor_msgs::Range::ConstPtr& msg) +{ + ir_arr.push_back(msg->range); +} +void ir7Callback(const sensor_msgs::Range::ConstPtr& msg) +{ + ir_arr.push_back(msg->range); +} +void ir8Callback(const sensor_msgs::Range::ConstPtr& msg) +{ + ir_arr.push_back(msg->range); +} + +int main(int argc, char **argv) +{ + + ros::init(argc, argv, "listener"); + + ros::NodeHandle n; + ros::Publisher light_curtain_pub = n.advertise("light_curtain", 1000); + std_msgs::Bool bool_msg; + ros::Subscriber sub = n.subscribe("ir", 1000, irCallback); + ros::Subscriber sub1 = n.subscribe("ir1", 1000, ir1Callback); + ros::Subscriber sub2 = n.subscribe("ir2", 1000, ir2Callback); + ros::Subscriber sub3 = n.subscribe("ir3", 1000, ir3Callback); + ros::Subscriber sub4 = n.subscribe("ir4", 1000, ir4Callback); + ros::Subscriber sub5 = n.subscribe("ir5", 1000, ir5Callback); + ros::Subscriber sub6 = n.subscribe("ir6", 1000, ir6Callback); + ros::Subscriber sub7 = n.subscribe("ir7", 1000, ir7Callback); + ros::Subscriber sub8 = n.subscribe("ir8", 1000, ir8Callback); + ros::Rate loop_rate(10); + + while (ros::ok()) + { + if (ir_arr.size() > 8){ + min_ir = *std::min_element(ir_arr.begin(), ir_arr.end()); + ir_arr.clear(); + } + if (min_ir >= 1.213) + bool_msg.data = false; + else + bool_msg.data = true; + light_curtain_pub.publish(bool_msg); + ros::spinOnce(); + + loop_rate.sleep(); + + } + + + return 0; + return 0; +} \ No newline at end of file diff --git a/mobile_manipulator/ifarlab_web/css/bootstrap.min.css b/mobile_manipulator/ifarlab_web/css/bootstrap.min.css new file mode 100644 index 0000000..6990cee --- /dev/null +++ b/mobile_manipulator/ifarlab_web/css/bootstrap.min.css @@ -0,0 +1,6 @@ +/*! + * Bootstrap v3.4.1 (https://getbootstrap.com/) + * Copyright 2011-2019 Twitter, Inc. + * Licensed under MIT (https://github.com/twbs/bootstrap/blob/master/LICENSE) + *//*! normalize.css v3.0.3 | MIT License | github.com/necolas/normalize.css */html{font-family:sans-serif;-ms-text-size-adjust:100%;-webkit-text-size-adjust:100%}body{margin:0}article,aside,details,figcaption,figure,footer,header,hgroup,main,menu,nav,section,summary{display:block}audio,canvas,progress,video{display:inline-block;vertical-align:baseline}audio:not([controls]){display:none;height:0}[hidden],template{display:none}a{background-color:transparent}a:active,a:hover{outline:0}abbr[title]{border-bottom:none;text-decoration:underline;-webkit-text-decoration:underline dotted;-moz-text-decoration:underline dotted;text-decoration:underline dotted}b,strong{font-weight:700}dfn{font-style:italic}h1{font-size:2em;margin:.67em 0}mark{background:#ff0;color:#000}small{font-size:80%}sub,sup{font-size:75%;line-height:0;position:relative;vertical-align:baseline}sup{top:-.5em}sub{bottom:-.25em}img{border:0}svg:not(:root){overflow:hidden}figure{margin:1em 40px}hr{-webkit-box-sizing:content-box;-moz-box-sizing:content-box;box-sizing:content-box;height:0}pre{overflow:auto}code,kbd,pre,samp{font-family:monospace,monospace;font-size:1em}button,input,optgroup,select,textarea{color:inherit;font:inherit;margin:0}button{overflow:visible}button,select{text-transform:none}button,html input[type=button],input[type=reset],input[type=submit]{-webkit-appearance:button;cursor:pointer}button[disabled],html input[disabled]{cursor:default}button::-moz-focus-inner,input::-moz-focus-inner{border:0;padding:0}input{line-height:normal}input[type=checkbox],input[type=radio]{-webkit-box-sizing:border-box;-moz-box-sizing:border-box;box-sizing:border-box;padding:0}input[type=number]::-webkit-inner-spin-button,input[type=number]::-webkit-outer-spin-button{height:auto}input[type=search]{-webkit-appearance:textfield;-webkit-box-sizing:content-box;-moz-box-sizing:content-box;box-sizing:content-box}input[type=search]::-webkit-search-cancel-button,input[type=search]::-webkit-search-decoration{-webkit-appearance:none}fieldset{border:1px solid silver;margin:0 2px;padding:.35em .625em .75em}legend{border:0;padding:0}textarea{overflow:auto}optgroup{font-weight:700}table{border-collapse:collapse;border-spacing:0}td,th{padding:0}/*! Source: https://github.com/h5bp/html5-boilerplate/blob/master/src/css/main.css */@media print{*,:after,:before{color:#000!important;text-shadow:none!important;background:0 0!important;-webkit-box-shadow:none!important;box-shadow:none!important}a,a:visited{text-decoration:underline}a[href]:after{content:" (" attr(href) ")"}abbr[title]:after{content:" (" attr(title) ")"}a[href^="#"]:after,a[href^="javascript:"]:after{content:""}blockquote,pre{border:1px solid #999;page-break-inside:avoid}thead{display:table-header-group}img,tr{page-break-inside:avoid}img{max-width:100%!important}h2,h3,p{orphans:3;widows:3}h2,h3{page-break-after:avoid}.navbar{display:none}.btn>.caret,.dropup>.btn>.caret{border-top-color:#000!important}.label{border:1px solid #000}.table{border-collapse:collapse!important}.table td,.table th{background-color:#fff!important}.table-bordered td,.table-bordered th{border:1px solid #ddd!important}}@font-face{font-family:"Glyphicons Halflings";src:url(../fonts/glyphicons-halflings-regular.eot);src:url(../fonts/glyphicons-halflings-regular.eot?#iefix) format("embedded-opentype"),url(../fonts/glyphicons-halflings-regular.woff2) format("woff2"),url(../fonts/glyphicons-halflings-regular.woff) format("woff"),url(../fonts/glyphicons-halflings-regular.ttf) format("truetype"),url(../fonts/glyphicons-halflings-regular.svg#glyphicons_halflingsregular) format("svg")}.glyphicon{position:relative;top:1px;display:inline-block;font-family:"Glyphicons Halflings";font-style:normal;font-weight:400;line-height:1;-webkit-font-smoothing:antialiased;-moz-osx-font-smoothing:grayscale}.glyphicon-asterisk:before{content:"\002a"}.glyphicon-plus:before{content:"\002b"}.glyphicon-eur:before,.glyphicon-euro:before{content:"\20ac"}.glyphicon-minus:before{content:"\2212"}.glyphicon-cloud:before{content:"\2601"}.glyphicon-envelope:before{content:"\2709"}.glyphicon-pencil:before{content:"\270f"}.glyphicon-glass:before{content:"\e001"}.glyphicon-music:before{content:"\e002"}.glyphicon-search:before{content:"\e003"}.glyphicon-heart:before{content:"\e005"}.glyphicon-star:before{content:"\e006"}.glyphicon-star-empty:before{content:"\e007"}.glyphicon-user:before{content:"\e008"}.glyphicon-film:before{content:"\e009"}.glyphicon-th-large:before{content:"\e010"}.glyphicon-th:before{content:"\e011"}.glyphicon-th-list:before{content:"\e012"}.glyphicon-ok:before{content:"\e013"}.glyphicon-remove:before{content:"\e014"}.glyphicon-zoom-in:before{content:"\e015"}.glyphicon-zoom-out:before{content:"\e016"}.glyphicon-off:before{content:"\e017"}.glyphicon-signal:before{content:"\e018"}.glyphicon-cog:before{content:"\e019"}.glyphicon-trash:before{content:"\e020"}.glyphicon-home:before{content:"\e021"}.glyphicon-file:before{content:"\e022"}.glyphicon-time:before{content:"\e023"}.glyphicon-road:before{content:"\e024"}.glyphicon-download-alt:before{content:"\e025"}.glyphicon-download:before{content:"\e026"}.glyphicon-upload:before{content:"\e027"}.glyphicon-inbox:before{content:"\e028"}.glyphicon-play-circle:before{content:"\e029"}.glyphicon-repeat:before{content:"\e030"}.glyphicon-refresh:before{content:"\e031"}.glyphicon-list-alt:before{content:"\e032"}.glyphicon-lock:before{content:"\e033"}.glyphicon-flag:before{content:"\e034"}.glyphicon-headphones:before{content:"\e035"}.glyphicon-volume-off:before{content:"\e036"}.glyphicon-volume-down:before{content:"\e037"}.glyphicon-volume-up:before{content:"\e038"}.glyphicon-qrcode:before{content:"\e039"}.glyphicon-barcode:before{content:"\e040"}.glyphicon-tag:before{content:"\e041"}.glyphicon-tags:before{content:"\e042"}.glyphicon-book:before{content:"\e043"}.glyphicon-bookmark:before{content:"\e044"}.glyphicon-print:before{content:"\e045"}.glyphicon-camera:before{content:"\e046"}.glyphicon-font:before{content:"\e047"}.glyphicon-bold:before{content:"\e048"}.glyphicon-italic:before{content:"\e049"}.glyphicon-text-height:before{content:"\e050"}.glyphicon-text-width:before{content:"\e051"}.glyphicon-align-left:before{content:"\e052"}.glyphicon-align-center:before{content:"\e053"}.glyphicon-align-right:before{content:"\e054"}.glyphicon-align-justify:before{content:"\e055"}.glyphicon-list:before{content:"\e056"}.glyphicon-indent-left:before{content:"\e057"}.glyphicon-indent-right:before{content:"\e058"}.glyphicon-facetime-video:before{content:"\e059"}.glyphicon-picture:before{content:"\e060"}.glyphicon-map-marker:before{content:"\e062"}.glyphicon-adjust:before{content:"\e063"}.glyphicon-tint:before{content:"\e064"}.glyphicon-edit:before{content:"\e065"}.glyphicon-share:before{content:"\e066"}.glyphicon-check:before{content:"\e067"}.glyphicon-move:before{content:"\e068"}.glyphicon-step-backward:before{content:"\e069"}.glyphicon-fast-backward:before{content:"\e070"}.glyphicon-backward:before{content:"\e071"}.glyphicon-play:before{content:"\e072"}.glyphicon-pause:before{content:"\e073"}.glyphicon-stop:before{content:"\e074"}.glyphicon-forward:before{content:"\e075"}.glyphicon-fast-forward:before{content:"\e076"}.glyphicon-step-forward:before{content:"\e077"}.glyphicon-eject:before{content:"\e078"}.glyphicon-chevron-left:before{content:"\e079"}.glyphicon-chevron-right:before{content:"\e080"}.glyphicon-plus-sign:before{content:"\e081"}.glyphicon-minus-sign:before{content:"\e082"}.glyphicon-remove-sign:before{content:"\e083"}.glyphicon-ok-sign:before{content:"\e084"}.glyphicon-question-sign:before{content:"\e085"}.glyphicon-info-sign:before{content:"\e086"}.glyphicon-screenshot:before{content:"\e087"}.glyphicon-remove-circle:before{content:"\e088"}.glyphicon-ok-circle:before{content:"\e089"}.glyphicon-ban-circle:before{content:"\e090"}.glyphicon-arrow-left:before{content:"\e091"}.glyphicon-arrow-right:before{content:"\e092"}.glyphicon-arrow-up:before{content:"\e093"}.glyphicon-arrow-down:before{content:"\e094"}.glyphicon-share-alt:before{content:"\e095"}.glyphicon-resize-full:before{content:"\e096"}.glyphicon-resize-small:before{content:"\e097"}.glyphicon-exclamation-sign:before{content:"\e101"}.glyphicon-gift:before{content:"\e102"}.glyphicon-leaf:before{content:"\e103"}.glyphicon-fire:before{content:"\e104"}.glyphicon-eye-open:before{content:"\e105"}.glyphicon-eye-close:before{content:"\e106"}.glyphicon-warning-sign:before{content:"\e107"}.glyphicon-plane:before{content:"\e108"}.glyphicon-calendar:before{content:"\e109"}.glyphicon-random:before{content:"\e110"}.glyphicon-comment:before{content:"\e111"}.glyphicon-magnet:before{content:"\e112"}.glyphicon-chevron-up:before{content:"\e113"}.glyphicon-chevron-down:before{content:"\e114"}.glyphicon-retweet:before{content:"\e115"}.glyphicon-shopping-cart:before{content:"\e116"}.glyphicon-folder-close:before{content:"\e117"}.glyphicon-folder-open:before{content:"\e118"}.glyphicon-resize-vertical:before{content:"\e119"}.glyphicon-resize-horizontal:before{content:"\e120"}.glyphicon-hdd:before{content:"\e121"}.glyphicon-bullhorn:before{content:"\e122"}.glyphicon-bell:before{content:"\e123"}.glyphicon-certificate:before{content:"\e124"}.glyphicon-thumbs-up:before{content:"\e125"}.glyphicon-thumbs-down:before{content:"\e126"}.glyphicon-hand-right:before{content:"\e127"}.glyphicon-hand-left:before{content:"\e128"}.glyphicon-hand-up:before{content:"\e129"}.glyphicon-hand-down:before{content:"\e130"}.glyphicon-circle-arrow-right:before{content:"\e131"}.glyphicon-circle-arrow-left:before{content:"\e132"}.glyphicon-circle-arrow-up:before{content:"\e133"}.glyphicon-circle-arrow-down:before{content:"\e134"}.glyphicon-globe:before{content:"\e135"}.glyphicon-wrench:before{content:"\e136"}.glyphicon-tasks:before{content:"\e137"}.glyphicon-filter:before{content:"\e138"}.glyphicon-briefcase:before{content:"\e139"}.glyphicon-fullscreen:before{content:"\e140"}.glyphicon-dashboard:before{content:"\e141"}.glyphicon-paperclip:before{content:"\e142"}.glyphicon-heart-empty:before{content:"\e143"}.glyphicon-link:before{content:"\e144"}.glyphicon-phone:before{content:"\e145"}.glyphicon-pushpin:before{content:"\e146"}.glyphicon-usd:before{content:"\e148"}.glyphicon-gbp:before{content:"\e149"}.glyphicon-sort:before{content:"\e150"}.glyphicon-sort-by-alphabet:before{content:"\e151"}.glyphicon-sort-by-alphabet-alt:before{content:"\e152"}.glyphicon-sort-by-order:before{content:"\e153"}.glyphicon-sort-by-order-alt:before{content:"\e154"}.glyphicon-sort-by-attributes:before{content:"\e155"}.glyphicon-sort-by-attributes-alt:before{content:"\e156"}.glyphicon-unchecked:before{content:"\e157"}.glyphicon-expand:before{content:"\e158"}.glyphicon-collapse-down:before{content:"\e159"}.glyphicon-collapse-up:before{content:"\e160"}.glyphicon-log-in:before{content:"\e161"}.glyphicon-flash:before{content:"\e162"}.glyphicon-log-out:before{content:"\e163"}.glyphicon-new-window:before{content:"\e164"}.glyphicon-record:before{content:"\e165"}.glyphicon-save:before{content:"\e166"}.glyphicon-open:before{content:"\e167"}.glyphicon-saved:before{content:"\e168"}.glyphicon-import:before{content:"\e169"}.glyphicon-export:before{content:"\e170"}.glyphicon-send:before{content:"\e171"}.glyphicon-floppy-disk:before{content:"\e172"}.glyphicon-floppy-saved:before{content:"\e173"}.glyphicon-floppy-remove:before{content:"\e174"}.glyphicon-floppy-save:before{content:"\e175"}.glyphicon-floppy-open:before{content:"\e176"}.glyphicon-credit-card:before{content:"\e177"}.glyphicon-transfer:before{content:"\e178"}.glyphicon-cutlery:before{content:"\e179"}.glyphicon-header:before{content:"\e180"}.glyphicon-compressed:before{content:"\e181"}.glyphicon-earphone:before{content:"\e182"}.glyphicon-phone-alt:before{content:"\e183"}.glyphicon-tower:before{content:"\e184"}.glyphicon-stats:before{content:"\e185"}.glyphicon-sd-video:before{content:"\e186"}.glyphicon-hd-video:before{content:"\e187"}.glyphicon-subtitles:before{content:"\e188"}.glyphicon-sound-stereo:before{content:"\e189"}.glyphicon-sound-dolby:before{content:"\e190"}.glyphicon-sound-5-1:before{content:"\e191"}.glyphicon-sound-6-1:before{content:"\e192"}.glyphicon-sound-7-1:before{content:"\e193"}.glyphicon-copyright-mark:before{content:"\e194"}.glyphicon-registration-mark:before{content:"\e195"}.glyphicon-cloud-download:before{content:"\e197"}.glyphicon-cloud-upload:before{content:"\e198"}.glyphicon-tree-conifer:before{content:"\e199"}.glyphicon-tree-deciduous:before{content:"\e200"}.glyphicon-cd:before{content:"\e201"}.glyphicon-save-file:before{content:"\e202"}.glyphicon-open-file:before{content:"\e203"}.glyphicon-level-up:before{content:"\e204"}.glyphicon-copy:before{content:"\e205"}.glyphicon-paste:before{content:"\e206"}.glyphicon-alert:before{content:"\e209"}.glyphicon-equalizer:before{content:"\e210"}.glyphicon-king:before{content:"\e211"}.glyphicon-queen:before{content:"\e212"}.glyphicon-pawn:before{content:"\e213"}.glyphicon-bishop:before{content:"\e214"}.glyphicon-knight:before{content:"\e215"}.glyphicon-baby-formula:before{content:"\e216"}.glyphicon-tent:before{content:"\26fa"}.glyphicon-blackboard:before{content:"\e218"}.glyphicon-bed:before{content:"\e219"}.glyphicon-apple:before{content:"\f8ff"}.glyphicon-erase:before{content:"\e221"}.glyphicon-hourglass:before{content:"\231b"}.glyphicon-lamp:before{content:"\e223"}.glyphicon-duplicate:before{content:"\e224"}.glyphicon-piggy-bank:before{content:"\e225"}.glyphicon-scissors:before{content:"\e226"}.glyphicon-bitcoin:before{content:"\e227"}.glyphicon-btc:before{content:"\e227"}.glyphicon-xbt:before{content:"\e227"}.glyphicon-yen:before{content:"\00a5"}.glyphicon-jpy:before{content:"\00a5"}.glyphicon-ruble:before{content:"\20bd"}.glyphicon-rub:before{content:"\20bd"}.glyphicon-scale:before{content:"\e230"}.glyphicon-ice-lolly:before{content:"\e231"}.glyphicon-ice-lolly-tasted:before{content:"\e232"}.glyphicon-education:before{content:"\e233"}.glyphicon-option-horizontal:before{content:"\e234"}.glyphicon-option-vertical:before{content:"\e235"}.glyphicon-menu-hamburger:before{content:"\e236"}.glyphicon-modal-window:before{content:"\e237"}.glyphicon-oil:before{content:"\e238"}.glyphicon-grain:before{content:"\e239"}.glyphicon-sunglasses:before{content:"\e240"}.glyphicon-text-size:before{content:"\e241"}.glyphicon-text-color:before{content:"\e242"}.glyphicon-text-background:before{content:"\e243"}.glyphicon-object-align-top:before{content:"\e244"}.glyphicon-object-align-bottom:before{content:"\e245"}.glyphicon-object-align-horizontal:before{content:"\e246"}.glyphicon-object-align-left:before{content:"\e247"}.glyphicon-object-align-vertical:before{content:"\e248"}.glyphicon-object-align-right:before{content:"\e249"}.glyphicon-triangle-right:before{content:"\e250"}.glyphicon-triangle-left:before{content:"\e251"}.glyphicon-triangle-bottom:before{content:"\e252"}.glyphicon-triangle-top:before{content:"\e253"}.glyphicon-console:before{content:"\e254"}.glyphicon-superscript:before{content:"\e255"}.glyphicon-subscript:before{content:"\e256"}.glyphicon-menu-left:before{content:"\e257"}.glyphicon-menu-right:before{content:"\e258"}.glyphicon-menu-down:before{content:"\e259"}.glyphicon-menu-up:before{content:"\e260"}*{-webkit-box-sizing:border-box;-moz-box-sizing:border-box;box-sizing:border-box}:after,:before{-webkit-box-sizing:border-box;-moz-box-sizing:border-box;box-sizing:border-box}html{font-size:10px;-webkit-tap-highlight-color:rgba(0,0,0,0)}body{font-family:"Helvetica Neue",Helvetica,Arial,sans-serif;font-size:14px;line-height:1.42857143;color:#333;background-color:#fff}button,input,select,textarea{font-family:inherit;font-size:inherit;line-height:inherit}a{color:#337ab7;text-decoration:none}a:focus,a:hover{color:#23527c;text-decoration:underline}a:focus{outline:5px auto -webkit-focus-ring-color;outline-offset:-2px}figure{margin:0}img{vertical-align:middle}.carousel-inner>.item>a>img,.carousel-inner>.item>img,.img-responsive,.thumbnail a>img,.thumbnail>img{display:block;max-width:100%;height:auto}.img-rounded{border-radius:6px}.img-thumbnail{padding:4px;line-height:1.42857143;background-color:#fff;border:1px solid #ddd;border-radius:4px;-webkit-transition:all .2s ease-in-out;-o-transition:all .2s ease-in-out;transition:all .2s ease-in-out;display:inline-block;max-width:100%;height:auto}.img-circle{border-radius:50%}hr{margin-top:20px;margin-bottom:20px;border:0;border-top:1px solid #eee}.sr-only{position:absolute;width:1px;height:1px;padding:0;margin:-1px;overflow:hidden;clip:rect(0,0,0,0);border:0}.sr-only-focusable:active,.sr-only-focusable:focus{position:static;width:auto;height:auto;margin:0;overflow:visible;clip:auto}[role=button]{cursor:pointer}.h1,.h2,.h3,.h4,.h5,.h6,h1,h2,h3,h4,h5,h6{font-family:inherit;font-weight:500;line-height:1.1;color:inherit}.h1 .small,.h1 small,.h2 .small,.h2 small,.h3 .small,.h3 small,.h4 .small,.h4 small,.h5 .small,.h5 small,.h6 .small,.h6 small,h1 .small,h1 small,h2 .small,h2 small,h3 .small,h3 small,h4 .small,h4 small,h5 .small,h5 small,h6 .small,h6 small{font-weight:400;line-height:1;color:#777}.h1,.h2,.h3,h1,h2,h3{margin-top:20px;margin-bottom:10px}.h1 .small,.h1 small,.h2 .small,.h2 small,.h3 .small,.h3 small,h1 .small,h1 small,h2 .small,h2 small,h3 .small,h3 small{font-size:65%}.h4,.h5,.h6,h4,h5,h6{margin-top:10px;margin-bottom:10px}.h4 .small,.h4 small,.h5 .small,.h5 small,.h6 .small,.h6 small,h4 .small,h4 small,h5 .small,h5 small,h6 .small,h6 small{font-size:75%}.h1,h1{font-size:36px}.h2,h2{font-size:30px}.h3,h3{font-size:24px}.h4,h4{font-size:18px}.h5,h5{font-size:14px}.h6,h6{font-size:12px}p{margin:0 0 10px}.lead{margin-bottom:20px;font-size:16px;font-weight:300;line-height:1.4}@media (min-width:768px){.lead{font-size:21px}}.small,small{font-size:85%}.mark,mark{padding:.2em;background-color:#fcf8e3}.text-left{text-align:left}.text-right{text-align:right}.text-center{text-align:center}.text-justify{text-align:justify}.text-nowrap{white-space:nowrap}.text-lowercase{text-transform:lowercase}.text-uppercase{text-transform:uppercase}.text-capitalize{text-transform:capitalize}.text-muted{color:#777}.text-primary{color:#337ab7}a.text-primary:focus,a.text-primary:hover{color:#286090}.text-success{color:#3c763d}a.text-success:focus,a.text-success:hover{color:#2b542c}.text-info{color:#31708f}a.text-info:focus,a.text-info:hover{color:#245269}.text-warning{color:#8a6d3b}a.text-warning:focus,a.text-warning:hover{color:#66512c}.text-danger{color:#a94442}a.text-danger:focus,a.text-danger:hover{color:#843534}.bg-primary{color:#fff;background-color:#337ab7}a.bg-primary:focus,a.bg-primary:hover{background-color:#286090}.bg-success{background-color:#dff0d8}a.bg-success:focus,a.bg-success:hover{background-color:#c1e2b3}.bg-info{background-color:#d9edf7}a.bg-info:focus,a.bg-info:hover{background-color:#afd9ee}.bg-warning{background-color:#fcf8e3}a.bg-warning:focus,a.bg-warning:hover{background-color:#f7ecb5}.bg-danger{background-color:#f2dede}a.bg-danger:focus,a.bg-danger:hover{background-color:#e4b9b9}.page-header{padding-bottom:9px;margin:40px 0 20px;border-bottom:1px solid #eee}ol,ul{margin-top:0;margin-bottom:10px}ol ol,ol ul,ul ol,ul ul{margin-bottom:0}.list-unstyled{padding-left:0;list-style:none}.list-inline{padding-left:0;list-style:none;margin-left:-5px}.list-inline>li{display:inline-block;padding-right:5px;padding-left:5px}dl{margin-top:0;margin-bottom:20px}dd,dt{line-height:1.42857143}dt{font-weight:700}dd{margin-left:0}@media (min-width:768px){.dl-horizontal dt{float:left;width:160px;clear:left;text-align:right;overflow:hidden;text-overflow:ellipsis;white-space:nowrap}.dl-horizontal dd{margin-left:180px}}abbr[data-original-title],abbr[title]{cursor:help}.initialism{font-size:90%;text-transform:uppercase}blockquote{padding:10px 20px;margin:0 0 20px;font-size:17.5px;border-left:5px solid #eee}blockquote ol:last-child,blockquote p:last-child,blockquote ul:last-child{margin-bottom:0}blockquote .small,blockquote footer,blockquote small{display:block;font-size:80%;line-height:1.42857143;color:#777}blockquote .small:before,blockquote footer:before,blockquote small:before{content:"\2014 \00A0"}.blockquote-reverse,blockquote.pull-right{padding-right:15px;padding-left:0;text-align:right;border-right:5px solid #eee;border-left:0}.blockquote-reverse .small:before,.blockquote-reverse footer:before,.blockquote-reverse small:before,blockquote.pull-right .small:before,blockquote.pull-right footer:before,blockquote.pull-right small:before{content:""}.blockquote-reverse .small:after,.blockquote-reverse footer:after,.blockquote-reverse small:after,blockquote.pull-right .small:after,blockquote.pull-right footer:after,blockquote.pull-right small:after{content:"\00A0 \2014"}address{margin-bottom:20px;font-style:normal;line-height:1.42857143}code,kbd,pre,samp{font-family:Menlo,Monaco,Consolas,"Courier New",monospace}code{padding:2px 4px;font-size:90%;color:#c7254e;background-color:#f9f2f4;border-radius:4px}kbd{padding:2px 4px;font-size:90%;color:#fff;background-color:#333;border-radius:3px;-webkit-box-shadow:inset 0 -1px 0 rgba(0,0,0,.25);box-shadow:inset 0 -1px 0 rgba(0,0,0,.25)}kbd kbd{padding:0;font-size:100%;font-weight:700;-webkit-box-shadow:none;box-shadow:none}pre{display:block;padding:9.5px;margin:0 0 10px;font-size:13px;line-height:1.42857143;color:#333;word-break:break-all;word-wrap:break-word;background-color:#f5f5f5;border:1px solid #ccc;border-radius:4px}pre code{padding:0;font-size:inherit;color:inherit;white-space:pre-wrap;background-color:transparent;border-radius:0}.pre-scrollable{max-height:340px;overflow-y:scroll}.container{padding-right:15px;padding-left:15px;margin-right:auto;margin-left:auto}@media (min-width:768px){.container{width:750px}}@media (min-width:992px){.container{width:970px}}@media (min-width:1200px){.container{width:1170px}}.container-fluid{padding-right:15px;padding-left:15px;margin-right:auto;margin-left:auto}.row{margin-right:-15px;margin-left:-15px}.row-no-gutters{margin-right:0;margin-left:0}.row-no-gutters [class*=col-]{padding-right:0;padding-left:0}.col-lg-1,.col-lg-10,.col-lg-11,.col-lg-12,.col-lg-2,.col-lg-3,.col-lg-4,.col-lg-5,.col-lg-6,.col-lg-7,.col-lg-8,.col-lg-9,.col-md-1,.col-md-10,.col-md-11,.col-md-12,.col-md-2,.col-md-3,.col-md-4,.col-md-5,.col-md-6,.col-md-7,.col-md-8,.col-md-9,.col-sm-1,.col-sm-10,.col-sm-11,.col-sm-12,.col-sm-2,.col-sm-3,.col-sm-4,.col-sm-5,.col-sm-6,.col-sm-7,.col-sm-8,.col-sm-9,.col-xs-1,.col-xs-10,.col-xs-11,.col-xs-12,.col-xs-2,.col-xs-3,.col-xs-4,.col-xs-5,.col-xs-6,.col-xs-7,.col-xs-8,.col-xs-9{position:relative;min-height:1px;padding-right:15px;padding-left:15px}.col-xs-1,.col-xs-10,.col-xs-11,.col-xs-12,.col-xs-2,.col-xs-3,.col-xs-4,.col-xs-5,.col-xs-6,.col-xs-7,.col-xs-8,.col-xs-9{float:left}.col-xs-12{width:100%}.col-xs-11{width:91.66666667%}.col-xs-10{width:83.33333333%}.col-xs-9{width:75%}.col-xs-8{width:66.66666667%}.col-xs-7{width:58.33333333%}.col-xs-6{width:50%}.col-xs-5{width:41.66666667%}.col-xs-4{width:33.33333333%}.col-xs-3{width:25%}.col-xs-2{width:16.66666667%}.col-xs-1{width:8.33333333%}.col-xs-pull-12{right:100%}.col-xs-pull-11{right:91.66666667%}.col-xs-pull-10{right:83.33333333%}.col-xs-pull-9{right:75%}.col-xs-pull-8{right:66.66666667%}.col-xs-pull-7{right:58.33333333%}.col-xs-pull-6{right:50%}.col-xs-pull-5{right:41.66666667%}.col-xs-pull-4{right:33.33333333%}.col-xs-pull-3{right:25%}.col-xs-pull-2{right:16.66666667%}.col-xs-pull-1{right:8.33333333%}.col-xs-pull-0{right:auto}.col-xs-push-12{left:100%}.col-xs-push-11{left:91.66666667%}.col-xs-push-10{left:83.33333333%}.col-xs-push-9{left:75%}.col-xs-push-8{left:66.66666667%}.col-xs-push-7{left:58.33333333%}.col-xs-push-6{left:50%}.col-xs-push-5{left:41.66666667%}.col-xs-push-4{left:33.33333333%}.col-xs-push-3{left:25%}.col-xs-push-2{left:16.66666667%}.col-xs-push-1{left:8.33333333%}.col-xs-push-0{left:auto}.col-xs-offset-12{margin-left:100%}.col-xs-offset-11{margin-left:91.66666667%}.col-xs-offset-10{margin-left:83.33333333%}.col-xs-offset-9{margin-left:75%}.col-xs-offset-8{margin-left:66.66666667%}.col-xs-offset-7{margin-left:58.33333333%}.col-xs-offset-6{margin-left:50%}.col-xs-offset-5{margin-left:41.66666667%}.col-xs-offset-4{margin-left:33.33333333%}.col-xs-offset-3{margin-left:25%}.col-xs-offset-2{margin-left:16.66666667%}.col-xs-offset-1{margin-left:8.33333333%}.col-xs-offset-0{margin-left:0}@media (min-width:768px){.col-sm-1,.col-sm-10,.col-sm-11,.col-sm-12,.col-sm-2,.col-sm-3,.col-sm-4,.col-sm-5,.col-sm-6,.col-sm-7,.col-sm-8,.col-sm-9{float:left}.col-sm-12{width:100%}.col-sm-11{width:91.66666667%}.col-sm-10{width:83.33333333%}.col-sm-9{width:75%}.col-sm-8{width:66.66666667%}.col-sm-7{width:58.33333333%}.col-sm-6{width:50%}.col-sm-5{width:41.66666667%}.col-sm-4{width:33.33333333%}.col-sm-3{width:25%}.col-sm-2{width:16.66666667%}.col-sm-1{width:8.33333333%}.col-sm-pull-12{right:100%}.col-sm-pull-11{right:91.66666667%}.col-sm-pull-10{right:83.33333333%}.col-sm-pull-9{right:75%}.col-sm-pull-8{right:66.66666667%}.col-sm-pull-7{right:58.33333333%}.col-sm-pull-6{right:50%}.col-sm-pull-5{right:41.66666667%}.col-sm-pull-4{right:33.33333333%}.col-sm-pull-3{right:25%}.col-sm-pull-2{right:16.66666667%}.col-sm-pull-1{right:8.33333333%}.col-sm-pull-0{right:auto}.col-sm-push-12{left:100%}.col-sm-push-11{left:91.66666667%}.col-sm-push-10{left:83.33333333%}.col-sm-push-9{left:75%}.col-sm-push-8{left:66.66666667%}.col-sm-push-7{left:58.33333333%}.col-sm-push-6{left:50%}.col-sm-push-5{left:41.66666667%}.col-sm-push-4{left:33.33333333%}.col-sm-push-3{left:25%}.col-sm-push-2{left:16.66666667%}.col-sm-push-1{left:8.33333333%}.col-sm-push-0{left:auto}.col-sm-offset-12{margin-left:100%}.col-sm-offset-11{margin-left:91.66666667%}.col-sm-offset-10{margin-left:83.33333333%}.col-sm-offset-9{margin-left:75%}.col-sm-offset-8{margin-left:66.66666667%}.col-sm-offset-7{margin-left:58.33333333%}.col-sm-offset-6{margin-left:50%}.col-sm-offset-5{margin-left:41.66666667%}.col-sm-offset-4{margin-left:33.33333333%}.col-sm-offset-3{margin-left:25%}.col-sm-offset-2{margin-left:16.66666667%}.col-sm-offset-1{margin-left:8.33333333%}.col-sm-offset-0{margin-left:0}}@media (min-width:992px){.col-md-1,.col-md-10,.col-md-11,.col-md-12,.col-md-2,.col-md-3,.col-md-4,.col-md-5,.col-md-6,.col-md-7,.col-md-8,.col-md-9{float:left}.col-md-12{width:100%}.col-md-11{width:91.66666667%}.col-md-10{width:83.33333333%}.col-md-9{width:75%}.col-md-8{width:66.66666667%}.col-md-7{width:58.33333333%}.col-md-6{width:50%}.col-md-5{width:41.66666667%}.col-md-4{width:33.33333333%}.col-md-3{width:25%}.col-md-2{width:16.66666667%}.col-md-1{width:8.33333333%}.col-md-pull-12{right:100%}.col-md-pull-11{right:91.66666667%}.col-md-pull-10{right:83.33333333%}.col-md-pull-9{right:75%}.col-md-pull-8{right:66.66666667%}.col-md-pull-7{right:58.33333333%}.col-md-pull-6{right:50%}.col-md-pull-5{right:41.66666667%}.col-md-pull-4{right:33.33333333%}.col-md-pull-3{right:25%}.col-md-pull-2{right:16.66666667%}.col-md-pull-1{right:8.33333333%}.col-md-pull-0{right:auto}.col-md-push-12{left:100%}.col-md-push-11{left:91.66666667%}.col-md-push-10{left:83.33333333%}.col-md-push-9{left:75%}.col-md-push-8{left:66.66666667%}.col-md-push-7{left:58.33333333%}.col-md-push-6{left:50%}.col-md-push-5{left:41.66666667%}.col-md-push-4{left:33.33333333%}.col-md-push-3{left:25%}.col-md-push-2{left:16.66666667%}.col-md-push-1{left:8.33333333%}.col-md-push-0{left:auto}.col-md-offset-12{margin-left:100%}.col-md-offset-11{margin-left:91.66666667%}.col-md-offset-10{margin-left:83.33333333%}.col-md-offset-9{margin-left:75%}.col-md-offset-8{margin-left:66.66666667%}.col-md-offset-7{margin-left:58.33333333%}.col-md-offset-6{margin-left:50%}.col-md-offset-5{margin-left:41.66666667%}.col-md-offset-4{margin-left:33.33333333%}.col-md-offset-3{margin-left:25%}.col-md-offset-2{margin-left:16.66666667%}.col-md-offset-1{margin-left:8.33333333%}.col-md-offset-0{margin-left:0}}@media (min-width:1200px){.col-lg-1,.col-lg-10,.col-lg-11,.col-lg-12,.col-lg-2,.col-lg-3,.col-lg-4,.col-lg-5,.col-lg-6,.col-lg-7,.col-lg-8,.col-lg-9{float:left}.col-lg-12{width:100%}.col-lg-11{width:91.66666667%}.col-lg-10{width:83.33333333%}.col-lg-9{width:75%}.col-lg-8{width:66.66666667%}.col-lg-7{width:58.33333333%}.col-lg-6{width:50%}.col-lg-5{width:41.66666667%}.col-lg-4{width:33.33333333%}.col-lg-3{width:25%}.col-lg-2{width:16.66666667%}.col-lg-1{width:8.33333333%}.col-lg-pull-12{right:100%}.col-lg-pull-11{right:91.66666667%}.col-lg-pull-10{right:83.33333333%}.col-lg-pull-9{right:75%}.col-lg-pull-8{right:66.66666667%}.col-lg-pull-7{right:58.33333333%}.col-lg-pull-6{right:50%}.col-lg-pull-5{right:41.66666667%}.col-lg-pull-4{right:33.33333333%}.col-lg-pull-3{right:25%}.col-lg-pull-2{right:16.66666667%}.col-lg-pull-1{right:8.33333333%}.col-lg-pull-0{right:auto}.col-lg-push-12{left:100%}.col-lg-push-11{left:91.66666667%}.col-lg-push-10{left:83.33333333%}.col-lg-push-9{left:75%}.col-lg-push-8{left:66.66666667%}.col-lg-push-7{left:58.33333333%}.col-lg-push-6{left:50%}.col-lg-push-5{left:41.66666667%}.col-lg-push-4{left:33.33333333%}.col-lg-push-3{left:25%}.col-lg-push-2{left:16.66666667%}.col-lg-push-1{left:8.33333333%}.col-lg-push-0{left:auto}.col-lg-offset-12{margin-left:100%}.col-lg-offset-11{margin-left:91.66666667%}.col-lg-offset-10{margin-left:83.33333333%}.col-lg-offset-9{margin-left:75%}.col-lg-offset-8{margin-left:66.66666667%}.col-lg-offset-7{margin-left:58.33333333%}.col-lg-offset-6{margin-left:50%}.col-lg-offset-5{margin-left:41.66666667%}.col-lg-offset-4{margin-left:33.33333333%}.col-lg-offset-3{margin-left:25%}.col-lg-offset-2{margin-left:16.66666667%}.col-lg-offset-1{margin-left:8.33333333%}.col-lg-offset-0{margin-left:0}}table{background-color:transparent}table col[class*=col-]{position:static;display:table-column;float:none}table td[class*=col-],table th[class*=col-]{position:static;display:table-cell;float:none}caption{padding-top:8px;padding-bottom:8px;color:#777;text-align:left}th{text-align:left}.table{width:100%;max-width:100%;margin-bottom:20px}.table>tbody>tr>td,.table>tbody>tr>th,.table>tfoot>tr>td,.table>tfoot>tr>th,.table>thead>tr>td,.table>thead>tr>th{padding:8px;line-height:1.42857143;vertical-align:top;border-top:1px solid #ddd}.table>thead>tr>th{vertical-align:bottom;border-bottom:2px solid #ddd}.table>caption+thead>tr:first-child>td,.table>caption+thead>tr:first-child>th,.table>colgroup+thead>tr:first-child>td,.table>colgroup+thead>tr:first-child>th,.table>thead:first-child>tr:first-child>td,.table>thead:first-child>tr:first-child>th{border-top:0}.table>tbody+tbody{border-top:2px solid #ddd}.table .table{background-color:#fff}.table-condensed>tbody>tr>td,.table-condensed>tbody>tr>th,.table-condensed>tfoot>tr>td,.table-condensed>tfoot>tr>th,.table-condensed>thead>tr>td,.table-condensed>thead>tr>th{padding:5px}.table-bordered{border:1px solid #ddd}.table-bordered>tbody>tr>td,.table-bordered>tbody>tr>th,.table-bordered>tfoot>tr>td,.table-bordered>tfoot>tr>th,.table-bordered>thead>tr>td,.table-bordered>thead>tr>th{border:1px solid #ddd}.table-bordered>thead>tr>td,.table-bordered>thead>tr>th{border-bottom-width:2px}.table-striped>tbody>tr:nth-of-type(odd){background-color:#f9f9f9}.table-hover>tbody>tr:hover{background-color:#f5f5f5}.table>tbody>tr.active>td,.table>tbody>tr.active>th,.table>tbody>tr>td.active,.table>tbody>tr>th.active,.table>tfoot>tr.active>td,.table>tfoot>tr.active>th,.table>tfoot>tr>td.active,.table>tfoot>tr>th.active,.table>thead>tr.active>td,.table>thead>tr.active>th,.table>thead>tr>td.active,.table>thead>tr>th.active{background-color:#f5f5f5}.table-hover>tbody>tr.active:hover>td,.table-hover>tbody>tr.active:hover>th,.table-hover>tbody>tr:hover>.active,.table-hover>tbody>tr>td.active:hover,.table-hover>tbody>tr>th.active:hover{background-color:#e8e8e8}.table>tbody>tr.success>td,.table>tbody>tr.success>th,.table>tbody>tr>td.success,.table>tbody>tr>th.success,.table>tfoot>tr.success>td,.table>tfoot>tr.success>th,.table>tfoot>tr>td.success,.table>tfoot>tr>th.success,.table>thead>tr.success>td,.table>thead>tr.success>th,.table>thead>tr>td.success,.table>thead>tr>th.success{background-color:#dff0d8}.table-hover>tbody>tr.success:hover>td,.table-hover>tbody>tr.success:hover>th,.table-hover>tbody>tr:hover>.success,.table-hover>tbody>tr>td.success:hover,.table-hover>tbody>tr>th.success:hover{background-color:#d0e9c6}.table>tbody>tr.info>td,.table>tbody>tr.info>th,.table>tbody>tr>td.info,.table>tbody>tr>th.info,.table>tfoot>tr.info>td,.table>tfoot>tr.info>th,.table>tfoot>tr>td.info,.table>tfoot>tr>th.info,.table>thead>tr.info>td,.table>thead>tr.info>th,.table>thead>tr>td.info,.table>thead>tr>th.info{background-color:#d9edf7}.table-hover>tbody>tr.info:hover>td,.table-hover>tbody>tr.info:hover>th,.table-hover>tbody>tr:hover>.info,.table-hover>tbody>tr>td.info:hover,.table-hover>tbody>tr>th.info:hover{background-color:#c4e3f3}.table>tbody>tr.warning>td,.table>tbody>tr.warning>th,.table>tbody>tr>td.warning,.table>tbody>tr>th.warning,.table>tfoot>tr.warning>td,.table>tfoot>tr.warning>th,.table>tfoot>tr>td.warning,.table>tfoot>tr>th.warning,.table>thead>tr.warning>td,.table>thead>tr.warning>th,.table>thead>tr>td.warning,.table>thead>tr>th.warning{background-color:#fcf8e3}.table-hover>tbody>tr.warning:hover>td,.table-hover>tbody>tr.warning:hover>th,.table-hover>tbody>tr:hover>.warning,.table-hover>tbody>tr>td.warning:hover,.table-hover>tbody>tr>th.warning:hover{background-color:#faf2cc}.table>tbody>tr.danger>td,.table>tbody>tr.danger>th,.table>tbody>tr>td.danger,.table>tbody>tr>th.danger,.table>tfoot>tr.danger>td,.table>tfoot>tr.danger>th,.table>tfoot>tr>td.danger,.table>tfoot>tr>th.danger,.table>thead>tr.danger>td,.table>thead>tr.danger>th,.table>thead>tr>td.danger,.table>thead>tr>th.danger{background-color:#f2dede}.table-hover>tbody>tr.danger:hover>td,.table-hover>tbody>tr.danger:hover>th,.table-hover>tbody>tr:hover>.danger,.table-hover>tbody>tr>td.danger:hover,.table-hover>tbody>tr>th.danger:hover{background-color:#ebcccc}.table-responsive{min-height:.01%;overflow-x:auto}@media screen and (max-width:767px){.table-responsive{width:100%;margin-bottom:15px;overflow-y:hidden;-ms-overflow-style:-ms-autohiding-scrollbar;border:1px solid #ddd}.table-responsive>.table{margin-bottom:0}.table-responsive>.table>tbody>tr>td,.table-responsive>.table>tbody>tr>th,.table-responsive>.table>tfoot>tr>td,.table-responsive>.table>tfoot>tr>th,.table-responsive>.table>thead>tr>td,.table-responsive>.table>thead>tr>th{white-space:nowrap}.table-responsive>.table-bordered{border:0}.table-responsive>.table-bordered>tbody>tr>td:first-child,.table-responsive>.table-bordered>tbody>tr>th:first-child,.table-responsive>.table-bordered>tfoot>tr>td:first-child,.table-responsive>.table-bordered>tfoot>tr>th:first-child,.table-responsive>.table-bordered>thead>tr>td:first-child,.table-responsive>.table-bordered>thead>tr>th:first-child{border-left:0}.table-responsive>.table-bordered>tbody>tr>td:last-child,.table-responsive>.table-bordered>tbody>tr>th:last-child,.table-responsive>.table-bordered>tfoot>tr>td:last-child,.table-responsive>.table-bordered>tfoot>tr>th:last-child,.table-responsive>.table-bordered>thead>tr>td:last-child,.table-responsive>.table-bordered>thead>tr>th:last-child{border-right:0}.table-responsive>.table-bordered>tbody>tr:last-child>td,.table-responsive>.table-bordered>tbody>tr:last-child>th,.table-responsive>.table-bordered>tfoot>tr:last-child>td,.table-responsive>.table-bordered>tfoot>tr:last-child>th{border-bottom:0}}fieldset{min-width:0;padding:0;margin:0;border:0}legend{display:block;width:100%;padding:0;margin-bottom:20px;font-size:21px;line-height:inherit;color:#333;border:0;border-bottom:1px solid #e5e5e5}label{display:inline-block;max-width:100%;margin-bottom:5px;font-weight:700}input[type=search]{-webkit-box-sizing:border-box;-moz-box-sizing:border-box;box-sizing:border-box;-webkit-appearance:none;-moz-appearance:none;appearance:none}input[type=checkbox],input[type=radio]{margin:4px 0 0;margin-top:1px\9;line-height:normal}fieldset[disabled] input[type=checkbox],fieldset[disabled] input[type=radio],input[type=checkbox].disabled,input[type=checkbox][disabled],input[type=radio].disabled,input[type=radio][disabled]{cursor:not-allowed}input[type=file]{display:block}input[type=range]{display:block;width:100%}select[multiple],select[size]{height:auto}input[type=checkbox]:focus,input[type=file]:focus,input[type=radio]:focus{outline:5px auto -webkit-focus-ring-color;outline-offset:-2px}output{display:block;padding-top:7px;font-size:14px;line-height:1.42857143;color:#555}.form-control{display:block;width:100%;height:34px;padding:6px 12px;font-size:14px;line-height:1.42857143;color:#555;background-color:#fff;background-image:none;border:1px solid #ccc;border-radius:4px;-webkit-box-shadow:inset 0 1px 1px rgba(0,0,0,.075);box-shadow:inset 0 1px 1px rgba(0,0,0,.075);-webkit-transition:border-color ease-in-out .15s,box-shadow ease-in-out .15s;-o-transition:border-color ease-in-out .15s,box-shadow ease-in-out .15s;-webkit-transition:border-color ease-in-out .15s,-webkit-box-shadow ease-in-out .15s;transition:border-color ease-in-out .15s,-webkit-box-shadow ease-in-out .15s;transition:border-color ease-in-out .15s,box-shadow ease-in-out .15s;transition:border-color ease-in-out .15s,box-shadow ease-in-out .15s,-webkit-box-shadow ease-in-out .15s}.form-control:focus{border-color:#66afe9;outline:0;-webkit-box-shadow:inset 0 1px 1px rgba(0,0,0,.075),0 0 8px rgba(102,175,233,.6);box-shadow:inset 0 1px 1px rgba(0,0,0,.075),0 0 8px rgba(102,175,233,.6)}.form-control::-moz-placeholder{color:#999;opacity:1}.form-control:-ms-input-placeholder{color:#999}.form-control::-webkit-input-placeholder{color:#999}.form-control::-ms-expand{background-color:transparent;border:0}.form-control[disabled],.form-control[readonly],fieldset[disabled] .form-control{background-color:#eee;opacity:1}.form-control[disabled],fieldset[disabled] .form-control{cursor:not-allowed}textarea.form-control{height:auto}@media screen and (-webkit-min-device-pixel-ratio:0){input[type=date].form-control,input[type=datetime-local].form-control,input[type=month].form-control,input[type=time].form-control{line-height:34px}.input-group-sm input[type=date],.input-group-sm input[type=datetime-local],.input-group-sm input[type=month],.input-group-sm input[type=time],input[type=date].input-sm,input[type=datetime-local].input-sm,input[type=month].input-sm,input[type=time].input-sm{line-height:30px}.input-group-lg input[type=date],.input-group-lg input[type=datetime-local],.input-group-lg input[type=month],.input-group-lg input[type=time],input[type=date].input-lg,input[type=datetime-local].input-lg,input[type=month].input-lg,input[type=time].input-lg{line-height:46px}}.form-group{margin-bottom:15px}.checkbox,.radio{position:relative;display:block;margin-top:10px;margin-bottom:10px}.checkbox.disabled label,.radio.disabled label,fieldset[disabled] .checkbox label,fieldset[disabled] .radio label{cursor:not-allowed}.checkbox label,.radio label{min-height:20px;padding-left:20px;margin-bottom:0;font-weight:400;cursor:pointer}.checkbox input[type=checkbox],.checkbox-inline input[type=checkbox],.radio input[type=radio],.radio-inline input[type=radio]{position:absolute;margin-top:4px\9;margin-left:-20px}.checkbox+.checkbox,.radio+.radio{margin-top:-5px}.checkbox-inline,.radio-inline{position:relative;display:inline-block;padding-left:20px;margin-bottom:0;font-weight:400;vertical-align:middle;cursor:pointer}.checkbox-inline.disabled,.radio-inline.disabled,fieldset[disabled] .checkbox-inline,fieldset[disabled] .radio-inline{cursor:not-allowed}.checkbox-inline+.checkbox-inline,.radio-inline+.radio-inline{margin-top:0;margin-left:10px}.form-control-static{min-height:34px;padding-top:7px;padding-bottom:7px;margin-bottom:0}.form-control-static.input-lg,.form-control-static.input-sm{padding-right:0;padding-left:0}.input-sm{height:30px;padding:5px 10px;font-size:12px;line-height:1.5;border-radius:3px}select.input-sm{height:30px;line-height:30px}select[multiple].input-sm,textarea.input-sm{height:auto}.form-group-sm .form-control{height:30px;padding:5px 10px;font-size:12px;line-height:1.5;border-radius:3px}.form-group-sm select.form-control{height:30px;line-height:30px}.form-group-sm select[multiple].form-control,.form-group-sm textarea.form-control{height:auto}.form-group-sm .form-control-static{height:30px;min-height:32px;padding:6px 10px;font-size:12px;line-height:1.5}.input-lg{height:46px;padding:10px 16px;font-size:18px;line-height:1.3333333;border-radius:6px}select.input-lg{height:46px;line-height:46px}select[multiple].input-lg,textarea.input-lg{height:auto}.form-group-lg .form-control{height:46px;padding:10px 16px;font-size:18px;line-height:1.3333333;border-radius:6px}.form-group-lg select.form-control{height:46px;line-height:46px}.form-group-lg select[multiple].form-control,.form-group-lg textarea.form-control{height:auto}.form-group-lg .form-control-static{height:46px;min-height:38px;padding:11px 16px;font-size:18px;line-height:1.3333333}.has-feedback{position:relative}.has-feedback .form-control{padding-right:42.5px}.form-control-feedback{position:absolute;top:0;right:0;z-index:2;display:block;width:34px;height:34px;line-height:34px;text-align:center;pointer-events:none}.form-group-lg .form-control+.form-control-feedback,.input-group-lg+.form-control-feedback,.input-lg+.form-control-feedback{width:46px;height:46px;line-height:46px}.form-group-sm .form-control+.form-control-feedback,.input-group-sm+.form-control-feedback,.input-sm+.form-control-feedback{width:30px;height:30px;line-height:30px}.has-success .checkbox,.has-success .checkbox-inline,.has-success .control-label,.has-success .help-block,.has-success .radio,.has-success .radio-inline,.has-success.checkbox label,.has-success.checkbox-inline label,.has-success.radio label,.has-success.radio-inline label{color:#3c763d}.has-success .form-control{border-color:#3c763d;-webkit-box-shadow:inset 0 1px 1px rgba(0,0,0,.075);box-shadow:inset 0 1px 1px rgba(0,0,0,.075)}.has-success .form-control:focus{border-color:#2b542c;-webkit-box-shadow:inset 0 1px 1px rgba(0,0,0,.075),0 0 6px #67b168;box-shadow:inset 0 1px 1px rgba(0,0,0,.075),0 0 6px #67b168}.has-success .input-group-addon{color:#3c763d;background-color:#dff0d8;border-color:#3c763d}.has-success .form-control-feedback{color:#3c763d}.has-warning .checkbox,.has-warning .checkbox-inline,.has-warning .control-label,.has-warning .help-block,.has-warning .radio,.has-warning .radio-inline,.has-warning.checkbox label,.has-warning.checkbox-inline label,.has-warning.radio label,.has-warning.radio-inline label{color:#8a6d3b}.has-warning .form-control{border-color:#8a6d3b;-webkit-box-shadow:inset 0 1px 1px rgba(0,0,0,.075);box-shadow:inset 0 1px 1px rgba(0,0,0,.075)}.has-warning .form-control:focus{border-color:#66512c;-webkit-box-shadow:inset 0 1px 1px rgba(0,0,0,.075),0 0 6px #c0a16b;box-shadow:inset 0 1px 1px rgba(0,0,0,.075),0 0 6px #c0a16b}.has-warning .input-group-addon{color:#8a6d3b;background-color:#fcf8e3;border-color:#8a6d3b}.has-warning .form-control-feedback{color:#8a6d3b}.has-error .checkbox,.has-error .checkbox-inline,.has-error .control-label,.has-error .help-block,.has-error .radio,.has-error .radio-inline,.has-error.checkbox label,.has-error.checkbox-inline label,.has-error.radio label,.has-error.radio-inline label{color:#a94442}.has-error .form-control{border-color:#a94442;-webkit-box-shadow:inset 0 1px 1px rgba(0,0,0,.075);box-shadow:inset 0 1px 1px rgba(0,0,0,.075)}.has-error .form-control:focus{border-color:#843534;-webkit-box-shadow:inset 0 1px 1px rgba(0,0,0,.075),0 0 6px #ce8483;box-shadow:inset 0 1px 1px rgba(0,0,0,.075),0 0 6px #ce8483}.has-error .input-group-addon{color:#a94442;background-color:#f2dede;border-color:#a94442}.has-error .form-control-feedback{color:#a94442}.has-feedback label~.form-control-feedback{top:25px}.has-feedback label.sr-only~.form-control-feedback{top:0}.help-block{display:block;margin-top:5px;margin-bottom:10px;color:#737373}@media (min-width:768px){.form-inline .form-group{display:inline-block;margin-bottom:0;vertical-align:middle}.form-inline .form-control{display:inline-block;width:auto;vertical-align:middle}.form-inline .form-control-static{display:inline-block}.form-inline .input-group{display:inline-table;vertical-align:middle}.form-inline .input-group .form-control,.form-inline .input-group .input-group-addon,.form-inline .input-group .input-group-btn{width:auto}.form-inline .input-group>.form-control{width:100%}.form-inline .control-label{margin-bottom:0;vertical-align:middle}.form-inline .checkbox,.form-inline .radio{display:inline-block;margin-top:0;margin-bottom:0;vertical-align:middle}.form-inline .checkbox label,.form-inline .radio label{padding-left:0}.form-inline .checkbox input[type=checkbox],.form-inline .radio input[type=radio]{position:relative;margin-left:0}.form-inline .has-feedback .form-control-feedback{top:0}}.form-horizontal .checkbox,.form-horizontal .checkbox-inline,.form-horizontal .radio,.form-horizontal .radio-inline{padding-top:7px;margin-top:0;margin-bottom:0}.form-horizontal .checkbox,.form-horizontal .radio{min-height:27px}.form-horizontal .form-group{margin-right:-15px;margin-left:-15px}@media (min-width:768px){.form-horizontal .control-label{padding-top:7px;margin-bottom:0;text-align:right}}.form-horizontal .has-feedback .form-control-feedback{right:15px}@media (min-width:768px){.form-horizontal .form-group-lg .control-label{padding-top:11px;font-size:18px}}@media (min-width:768px){.form-horizontal .form-group-sm .control-label{padding-top:6px;font-size:12px}}.btn{display:inline-block;margin-bottom:0;font-weight:400;text-align:center;white-space:nowrap;vertical-align:middle;-ms-touch-action:manipulation;touch-action:manipulation;cursor:pointer;background-image:none;border:1px solid transparent;padding:6px 12px;font-size:14px;line-height:1.42857143;border-radius:4px;-webkit-user-select:none;-moz-user-select:none;-ms-user-select:none;user-select:none}.btn.active.focus,.btn.active:focus,.btn.focus,.btn:active.focus,.btn:active:focus,.btn:focus{outline:5px auto -webkit-focus-ring-color;outline-offset:-2px}.btn.focus,.btn:focus,.btn:hover{color:#333;text-decoration:none}.btn.active,.btn:active{background-image:none;outline:0;-webkit-box-shadow:inset 0 3px 5px rgba(0,0,0,.125);box-shadow:inset 0 3px 5px rgba(0,0,0,.125)}.btn.disabled,.btn[disabled],fieldset[disabled] .btn{cursor:not-allowed;filter:alpha(opacity=65);opacity:.65;-webkit-box-shadow:none;box-shadow:none}a.btn.disabled,fieldset[disabled] a.btn{pointer-events:none}.btn-default{color:#333;background-color:#fff;border-color:#ccc}.btn-default.focus,.btn-default:focus{color:#333;background-color:#e6e6e6;border-color:#8c8c8c}.btn-default:hover{color:#333;background-color:#e6e6e6;border-color:#adadad}.btn-default.active,.btn-default:active,.open>.dropdown-toggle.btn-default{color:#333;background-color:#e6e6e6;background-image:none;border-color:#adadad}.btn-default.active.focus,.btn-default.active:focus,.btn-default.active:hover,.btn-default:active.focus,.btn-default:active:focus,.btn-default:active:hover,.open>.dropdown-toggle.btn-default.focus,.open>.dropdown-toggle.btn-default:focus,.open>.dropdown-toggle.btn-default:hover{color:#333;background-color:#d4d4d4;border-color:#8c8c8c}.btn-default.disabled.focus,.btn-default.disabled:focus,.btn-default.disabled:hover,.btn-default[disabled].focus,.btn-default[disabled]:focus,.btn-default[disabled]:hover,fieldset[disabled] .btn-default.focus,fieldset[disabled] .btn-default:focus,fieldset[disabled] .btn-default:hover{background-color:#fff;border-color:#ccc}.btn-default .badge{color:#fff;background-color:#333}.btn-primary{color:#fff;background-color:#337ab7;border-color:#2e6da4}.btn-primary.focus,.btn-primary:focus{color:#fff;background-color:#286090;border-color:#122b40}.btn-primary:hover{color:#fff;background-color:#286090;border-color:#204d74}.btn-primary.active,.btn-primary:active,.open>.dropdown-toggle.btn-primary{color:#fff;background-color:#286090;background-image:none;border-color:#204d74}.btn-primary.active.focus,.btn-primary.active:focus,.btn-primary.active:hover,.btn-primary:active.focus,.btn-primary:active:focus,.btn-primary:active:hover,.open>.dropdown-toggle.btn-primary.focus,.open>.dropdown-toggle.btn-primary:focus,.open>.dropdown-toggle.btn-primary:hover{color:#fff;background-color:#204d74;border-color:#122b40}.btn-primary.disabled.focus,.btn-primary.disabled:focus,.btn-primary.disabled:hover,.btn-primary[disabled].focus,.btn-primary[disabled]:focus,.btn-primary[disabled]:hover,fieldset[disabled] .btn-primary.focus,fieldset[disabled] .btn-primary:focus,fieldset[disabled] .btn-primary:hover{background-color:#337ab7;border-color:#2e6da4}.btn-primary .badge{color:#337ab7;background-color:#fff}.btn-success{color:#fff;background-color:#5cb85c;border-color:#4cae4c}.btn-success.focus,.btn-success:focus{color:#fff;background-color:#449d44;border-color:#255625}.btn-success:hover{color:#fff;background-color:#449d44;border-color:#398439}.btn-success.active,.btn-success:active,.open>.dropdown-toggle.btn-success{color:#fff;background-color:#449d44;background-image:none;border-color:#398439}.btn-success.active.focus,.btn-success.active:focus,.btn-success.active:hover,.btn-success:active.focus,.btn-success:active:focus,.btn-success:active:hover,.open>.dropdown-toggle.btn-success.focus,.open>.dropdown-toggle.btn-success:focus,.open>.dropdown-toggle.btn-success:hover{color:#fff;background-color:#398439;border-color:#255625}.btn-success.disabled.focus,.btn-success.disabled:focus,.btn-success.disabled:hover,.btn-success[disabled].focus,.btn-success[disabled]:focus,.btn-success[disabled]:hover,fieldset[disabled] .btn-success.focus,fieldset[disabled] .btn-success:focus,fieldset[disabled] .btn-success:hover{background-color:#5cb85c;border-color:#4cae4c}.btn-success .badge{color:#5cb85c;background-color:#fff}.btn-info{color:#fff;background-color:#5bc0de;border-color:#46b8da}.btn-info.focus,.btn-info:focus{color:#fff;background-color:#31b0d5;border-color:#1b6d85}.btn-info:hover{color:#fff;background-color:#31b0d5;border-color:#269abc}.btn-info.active,.btn-info:active,.open>.dropdown-toggle.btn-info{color:#fff;background-color:#31b0d5;background-image:none;border-color:#269abc}.btn-info.active.focus,.btn-info.active:focus,.btn-info.active:hover,.btn-info:active.focus,.btn-info:active:focus,.btn-info:active:hover,.open>.dropdown-toggle.btn-info.focus,.open>.dropdown-toggle.btn-info:focus,.open>.dropdown-toggle.btn-info:hover{color:#fff;background-color:#269abc;border-color:#1b6d85}.btn-info.disabled.focus,.btn-info.disabled:focus,.btn-info.disabled:hover,.btn-info[disabled].focus,.btn-info[disabled]:focus,.btn-info[disabled]:hover,fieldset[disabled] .btn-info.focus,fieldset[disabled] .btn-info:focus,fieldset[disabled] .btn-info:hover{background-color:#5bc0de;border-color:#46b8da}.btn-info .badge{color:#5bc0de;background-color:#fff}.btn-warning{color:#fff;background-color:#f0ad4e;border-color:#eea236}.btn-warning.focus,.btn-warning:focus{color:#fff;background-color:#ec971f;border-color:#985f0d}.btn-warning:hover{color:#fff;background-color:#ec971f;border-color:#d58512}.btn-warning.active,.btn-warning:active,.open>.dropdown-toggle.btn-warning{color:#fff;background-color:#ec971f;background-image:none;border-color:#d58512}.btn-warning.active.focus,.btn-warning.active:focus,.btn-warning.active:hover,.btn-warning:active.focus,.btn-warning:active:focus,.btn-warning:active:hover,.open>.dropdown-toggle.btn-warning.focus,.open>.dropdown-toggle.btn-warning:focus,.open>.dropdown-toggle.btn-warning:hover{color:#fff;background-color:#d58512;border-color:#985f0d}.btn-warning.disabled.focus,.btn-warning.disabled:focus,.btn-warning.disabled:hover,.btn-warning[disabled].focus,.btn-warning[disabled]:focus,.btn-warning[disabled]:hover,fieldset[disabled] .btn-warning.focus,fieldset[disabled] .btn-warning:focus,fieldset[disabled] .btn-warning:hover{background-color:#f0ad4e;border-color:#eea236}.btn-warning .badge{color:#f0ad4e;background-color:#fff}.btn-danger{color:#fff;background-color:#d9534f;border-color:#d43f3a}.btn-danger.focus,.btn-danger:focus{color:#fff;background-color:#c9302c;border-color:#761c19}.btn-danger:hover{color:#fff;background-color:#c9302c;border-color:#ac2925}.btn-danger.active,.btn-danger:active,.open>.dropdown-toggle.btn-danger{color:#fff;background-color:#c9302c;background-image:none;border-color:#ac2925}.btn-danger.active.focus,.btn-danger.active:focus,.btn-danger.active:hover,.btn-danger:active.focus,.btn-danger:active:focus,.btn-danger:active:hover,.open>.dropdown-toggle.btn-danger.focus,.open>.dropdown-toggle.btn-danger:focus,.open>.dropdown-toggle.btn-danger:hover{color:#fff;background-color:#ac2925;border-color:#761c19}.btn-danger.disabled.focus,.btn-danger.disabled:focus,.btn-danger.disabled:hover,.btn-danger[disabled].focus,.btn-danger[disabled]:focus,.btn-danger[disabled]:hover,fieldset[disabled] .btn-danger.focus,fieldset[disabled] .btn-danger:focus,fieldset[disabled] .btn-danger:hover{background-color:#d9534f;border-color:#d43f3a}.btn-danger .badge{color:#d9534f;background-color:#fff}.btn-link{font-weight:400;color:#337ab7;border-radius:0}.btn-link,.btn-link.active,.btn-link:active,.btn-link[disabled],fieldset[disabled] .btn-link{background-color:transparent;-webkit-box-shadow:none;box-shadow:none}.btn-link,.btn-link:active,.btn-link:focus,.btn-link:hover{border-color:transparent}.btn-link:focus,.btn-link:hover{color:#23527c;text-decoration:underline;background-color:transparent}.btn-link[disabled]:focus,.btn-link[disabled]:hover,fieldset[disabled] .btn-link:focus,fieldset[disabled] .btn-link:hover{color:#777;text-decoration:none}.btn-group-lg>.btn,.btn-lg{padding:10px 16px;font-size:18px;line-height:1.3333333;border-radius:6px}.btn-group-sm>.btn,.btn-sm{padding:5px 10px;font-size:12px;line-height:1.5;border-radius:3px}.btn-group-xs>.btn,.btn-xs{padding:1px 5px;font-size:12px;line-height:1.5;border-radius:3px}.btn-block{display:block;width:100%}.btn-block+.btn-block{margin-top:5px}input[type=button].btn-block,input[type=reset].btn-block,input[type=submit].btn-block{width:100%}.fade{opacity:0;-webkit-transition:opacity .15s linear;-o-transition:opacity .15s linear;transition:opacity .15s linear}.fade.in{opacity:1}.collapse{display:none}.collapse.in{display:block}tr.collapse.in{display:table-row}tbody.collapse.in{display:table-row-group}.collapsing{position:relative;height:0;overflow:hidden;-webkit-transition-property:height,visibility;-o-transition-property:height,visibility;transition-property:height,visibility;-webkit-transition-duration:.35s;-o-transition-duration:.35s;transition-duration:.35s;-webkit-transition-timing-function:ease;-o-transition-timing-function:ease;transition-timing-function:ease}.caret{display:inline-block;width:0;height:0;margin-left:2px;vertical-align:middle;border-top:4px dashed;border-top:4px solid\9;border-right:4px solid transparent;border-left:4px solid transparent}.dropdown,.dropup{position:relative}.dropdown-toggle:focus{outline:0}.dropdown-menu{position:absolute;top:100%;left:0;z-index:1000;display:none;float:left;min-width:160px;padding:5px 0;margin:2px 0 0;font-size:14px;text-align:left;list-style:none;background-color:#fff;background-clip:padding-box;border:1px solid #ccc;border:1px solid rgba(0,0,0,.15);border-radius:4px;-webkit-box-shadow:0 6px 12px rgba(0,0,0,.175);box-shadow:0 6px 12px rgba(0,0,0,.175)}.dropdown-menu.pull-right{right:0;left:auto}.dropdown-menu .divider{height:1px;margin:9px 0;overflow:hidden;background-color:#e5e5e5}.dropdown-menu>li>a{display:block;padding:3px 20px;clear:both;font-weight:400;line-height:1.42857143;color:#333;white-space:nowrap}.dropdown-menu>li>a:focus,.dropdown-menu>li>a:hover{color:#262626;text-decoration:none;background-color:#f5f5f5}.dropdown-menu>.active>a,.dropdown-menu>.active>a:focus,.dropdown-menu>.active>a:hover{color:#fff;text-decoration:none;background-color:#337ab7;outline:0}.dropdown-menu>.disabled>a,.dropdown-menu>.disabled>a:focus,.dropdown-menu>.disabled>a:hover{color:#777}.dropdown-menu>.disabled>a:focus,.dropdown-menu>.disabled>a:hover{text-decoration:none;cursor:not-allowed;background-color:transparent;background-image:none;filter:progid:DXImageTransform.Microsoft.gradient(enabled=false)}.open>.dropdown-menu{display:block}.open>a{outline:0}.dropdown-menu-right{right:0;left:auto}.dropdown-menu-left{right:auto;left:0}.dropdown-header{display:block;padding:3px 20px;font-size:12px;line-height:1.42857143;color:#777;white-space:nowrap}.dropdown-backdrop{position:fixed;top:0;right:0;bottom:0;left:0;z-index:990}.pull-right>.dropdown-menu{right:0;left:auto}.dropup .caret,.navbar-fixed-bottom .dropdown .caret{content:"";border-top:0;border-bottom:4px dashed;border-bottom:4px solid\9}.dropup .dropdown-menu,.navbar-fixed-bottom .dropdown .dropdown-menu{top:auto;bottom:100%;margin-bottom:2px}@media (min-width:768px){.navbar-right .dropdown-menu{right:0;left:auto}.navbar-right .dropdown-menu-left{right:auto;left:0}}.btn-group,.btn-group-vertical{position:relative;display:inline-block;vertical-align:middle}.btn-group-vertical>.btn,.btn-group>.btn{position:relative;float:left}.btn-group-vertical>.btn.active,.btn-group-vertical>.btn:active,.btn-group-vertical>.btn:focus,.btn-group-vertical>.btn:hover,.btn-group>.btn.active,.btn-group>.btn:active,.btn-group>.btn:focus,.btn-group>.btn:hover{z-index:2}.btn-group .btn+.btn,.btn-group .btn+.btn-group,.btn-group .btn-group+.btn,.btn-group .btn-group+.btn-group{margin-left:-1px}.btn-toolbar{margin-left:-5px}.btn-toolbar .btn,.btn-toolbar .btn-group,.btn-toolbar .input-group{float:left}.btn-toolbar>.btn,.btn-toolbar>.btn-group,.btn-toolbar>.input-group{margin-left:5px}.btn-group>.btn:not(:first-child):not(:last-child):not(.dropdown-toggle){border-radius:0}.btn-group>.btn:first-child{margin-left:0}.btn-group>.btn:first-child:not(:last-child):not(.dropdown-toggle){border-top-right-radius:0;border-bottom-right-radius:0}.btn-group>.btn:last-child:not(:first-child),.btn-group>.dropdown-toggle:not(:first-child){border-top-left-radius:0;border-bottom-left-radius:0}.btn-group>.btn-group{float:left}.btn-group>.btn-group:not(:first-child):not(:last-child)>.btn{border-radius:0}.btn-group>.btn-group:first-child:not(:last-child)>.btn:last-child,.btn-group>.btn-group:first-child:not(:last-child)>.dropdown-toggle{border-top-right-radius:0;border-bottom-right-radius:0}.btn-group>.btn-group:last-child:not(:first-child)>.btn:first-child{border-top-left-radius:0;border-bottom-left-radius:0}.btn-group .dropdown-toggle:active,.btn-group.open .dropdown-toggle{outline:0}.btn-group>.btn+.dropdown-toggle{padding-right:8px;padding-left:8px}.btn-group>.btn-lg+.dropdown-toggle{padding-right:12px;padding-left:12px}.btn-group.open .dropdown-toggle{-webkit-box-shadow:inset 0 3px 5px rgba(0,0,0,.125);box-shadow:inset 0 3px 5px rgba(0,0,0,.125)}.btn-group.open .dropdown-toggle.btn-link{-webkit-box-shadow:none;box-shadow:none}.btn .caret{margin-left:0}.btn-lg .caret{border-width:5px 5px 0;border-bottom-width:0}.dropup .btn-lg .caret{border-width:0 5px 5px}.btn-group-vertical>.btn,.btn-group-vertical>.btn-group,.btn-group-vertical>.btn-group>.btn{display:block;float:none;width:100%;max-width:100%}.btn-group-vertical>.btn-group>.btn{float:none}.btn-group-vertical>.btn+.btn,.btn-group-vertical>.btn+.btn-group,.btn-group-vertical>.btn-group+.btn,.btn-group-vertical>.btn-group+.btn-group{margin-top:-1px;margin-left:0}.btn-group-vertical>.btn:not(:first-child):not(:last-child){border-radius:0}.btn-group-vertical>.btn:first-child:not(:last-child){border-top-left-radius:4px;border-top-right-radius:4px;border-bottom-right-radius:0;border-bottom-left-radius:0}.btn-group-vertical>.btn:last-child:not(:first-child){border-top-left-radius:0;border-top-right-radius:0;border-bottom-right-radius:4px;border-bottom-left-radius:4px}.btn-group-vertical>.btn-group:not(:first-child):not(:last-child)>.btn{border-radius:0}.btn-group-vertical>.btn-group:first-child:not(:last-child)>.btn:last-child,.btn-group-vertical>.btn-group:first-child:not(:last-child)>.dropdown-toggle{border-bottom-right-radius:0;border-bottom-left-radius:0}.btn-group-vertical>.btn-group:last-child:not(:first-child)>.btn:first-child{border-top-left-radius:0;border-top-right-radius:0}.btn-group-justified{display:table;width:100%;table-layout:fixed;border-collapse:separate}.btn-group-justified>.btn,.btn-group-justified>.btn-group{display:table-cell;float:none;width:1%}.btn-group-justified>.btn-group .btn{width:100%}.btn-group-justified>.btn-group .dropdown-menu{left:auto}[data-toggle=buttons]>.btn input[type=checkbox],[data-toggle=buttons]>.btn input[type=radio],[data-toggle=buttons]>.btn-group>.btn input[type=checkbox],[data-toggle=buttons]>.btn-group>.btn input[type=radio]{position:absolute;clip:rect(0,0,0,0);pointer-events:none}.input-group{position:relative;display:table;border-collapse:separate}.input-group[class*=col-]{float:none;padding-right:0;padding-left:0}.input-group .form-control{position:relative;z-index:2;float:left;width:100%;margin-bottom:0}.input-group .form-control:focus{z-index:3}.input-group-lg>.form-control,.input-group-lg>.input-group-addon,.input-group-lg>.input-group-btn>.btn{height:46px;padding:10px 16px;font-size:18px;line-height:1.3333333;border-radius:6px}select.input-group-lg>.form-control,select.input-group-lg>.input-group-addon,select.input-group-lg>.input-group-btn>.btn{height:46px;line-height:46px}select[multiple].input-group-lg>.form-control,select[multiple].input-group-lg>.input-group-addon,select[multiple].input-group-lg>.input-group-btn>.btn,textarea.input-group-lg>.form-control,textarea.input-group-lg>.input-group-addon,textarea.input-group-lg>.input-group-btn>.btn{height:auto}.input-group-sm>.form-control,.input-group-sm>.input-group-addon,.input-group-sm>.input-group-btn>.btn{height:30px;padding:5px 10px;font-size:12px;line-height:1.5;border-radius:3px}select.input-group-sm>.form-control,select.input-group-sm>.input-group-addon,select.input-group-sm>.input-group-btn>.btn{height:30px;line-height:30px}select[multiple].input-group-sm>.form-control,select[multiple].input-group-sm>.input-group-addon,select[multiple].input-group-sm>.input-group-btn>.btn,textarea.input-group-sm>.form-control,textarea.input-group-sm>.input-group-addon,textarea.input-group-sm>.input-group-btn>.btn{height:auto}.input-group .form-control,.input-group-addon,.input-group-btn{display:table-cell}.input-group .form-control:not(:first-child):not(:last-child),.input-group-addon:not(:first-child):not(:last-child),.input-group-btn:not(:first-child):not(:last-child){border-radius:0}.input-group-addon,.input-group-btn{width:1%;white-space:nowrap;vertical-align:middle}.input-group-addon{padding:6px 12px;font-size:14px;font-weight:400;line-height:1;color:#555;text-align:center;background-color:#eee;border:1px solid #ccc;border-radius:4px}.input-group-addon.input-sm{padding:5px 10px;font-size:12px;border-radius:3px}.input-group-addon.input-lg{padding:10px 16px;font-size:18px;border-radius:6px}.input-group-addon input[type=checkbox],.input-group-addon input[type=radio]{margin-top:0}.input-group .form-control:first-child,.input-group-addon:first-child,.input-group-btn:first-child>.btn,.input-group-btn:first-child>.btn-group>.btn,.input-group-btn:first-child>.dropdown-toggle,.input-group-btn:last-child>.btn-group:not(:last-child)>.btn,.input-group-btn:last-child>.btn:not(:last-child):not(.dropdown-toggle){border-top-right-radius:0;border-bottom-right-radius:0}.input-group-addon:first-child{border-right:0}.input-group .form-control:last-child,.input-group-addon:last-child,.input-group-btn:first-child>.btn-group:not(:first-child)>.btn,.input-group-btn:first-child>.btn:not(:first-child),.input-group-btn:last-child>.btn,.input-group-btn:last-child>.btn-group>.btn,.input-group-btn:last-child>.dropdown-toggle{border-top-left-radius:0;border-bottom-left-radius:0}.input-group-addon:last-child{border-left:0}.input-group-btn{position:relative;font-size:0;white-space:nowrap}.input-group-btn>.btn{position:relative}.input-group-btn>.btn+.btn{margin-left:-1px}.input-group-btn>.btn:active,.input-group-btn>.btn:focus,.input-group-btn>.btn:hover{z-index:2}.input-group-btn:first-child>.btn,.input-group-btn:first-child>.btn-group{margin-right:-1px}.input-group-btn:last-child>.btn,.input-group-btn:last-child>.btn-group{z-index:2;margin-left:-1px}.nav{padding-left:0;margin-bottom:0;list-style:none}.nav>li{position:relative;display:block}.nav>li>a{position:relative;display:block;padding:10px 15px}.nav>li>a:focus,.nav>li>a:hover{text-decoration:none;background-color:#eee}.nav>li.disabled>a{color:#777}.nav>li.disabled>a:focus,.nav>li.disabled>a:hover{color:#777;text-decoration:none;cursor:not-allowed;background-color:transparent}.nav .open>a,.nav .open>a:focus,.nav .open>a:hover{background-color:#eee;border-color:#337ab7}.nav .nav-divider{height:1px;margin:9px 0;overflow:hidden;background-color:#e5e5e5}.nav>li>a>img{max-width:none}.nav-tabs{border-bottom:1px solid #ddd}.nav-tabs>li{float:left;margin-bottom:-1px}.nav-tabs>li>a{margin-right:2px;line-height:1.42857143;border:1px solid transparent;border-radius:4px 4px 0 0}.nav-tabs>li>a:hover{border-color:#eee #eee #ddd}.nav-tabs>li.active>a,.nav-tabs>li.active>a:focus,.nav-tabs>li.active>a:hover{color:#555;cursor:default;background-color:#fff;border:1px solid #ddd;border-bottom-color:transparent}.nav-tabs.nav-justified{width:100%;border-bottom:0}.nav-tabs.nav-justified>li{float:none}.nav-tabs.nav-justified>li>a{margin-bottom:5px;text-align:center}.nav-tabs.nav-justified>.dropdown .dropdown-menu{top:auto;left:auto}@media (min-width:768px){.nav-tabs.nav-justified>li{display:table-cell;width:1%}.nav-tabs.nav-justified>li>a{margin-bottom:0}}.nav-tabs.nav-justified>li>a{margin-right:0;border-radius:4px}.nav-tabs.nav-justified>.active>a,.nav-tabs.nav-justified>.active>a:focus,.nav-tabs.nav-justified>.active>a:hover{border:1px solid #ddd}@media (min-width:768px){.nav-tabs.nav-justified>li>a{border-bottom:1px solid #ddd;border-radius:4px 4px 0 0}.nav-tabs.nav-justified>.active>a,.nav-tabs.nav-justified>.active>a:focus,.nav-tabs.nav-justified>.active>a:hover{border-bottom-color:#fff}}.nav-pills>li{float:left}.nav-pills>li>a{border-radius:4px}.nav-pills>li+li{margin-left:2px}.nav-pills>li.active>a,.nav-pills>li.active>a:focus,.nav-pills>li.active>a:hover{color:#fff;background-color:#337ab7}.nav-stacked>li{float:none}.nav-stacked>li+li{margin-top:2px;margin-left:0}.nav-justified{width:100%}.nav-justified>li{float:none}.nav-justified>li>a{margin-bottom:5px;text-align:center}.nav-justified>.dropdown .dropdown-menu{top:auto;left:auto}@media (min-width:768px){.nav-justified>li{display:table-cell;width:1%}.nav-justified>li>a{margin-bottom:0}}.nav-tabs-justified{border-bottom:0}.nav-tabs-justified>li>a{margin-right:0;border-radius:4px}.nav-tabs-justified>.active>a,.nav-tabs-justified>.active>a:focus,.nav-tabs-justified>.active>a:hover{border:1px solid #ddd}@media (min-width:768px){.nav-tabs-justified>li>a{border-bottom:1px solid #ddd;border-radius:4px 4px 0 0}.nav-tabs-justified>.active>a,.nav-tabs-justified>.active>a:focus,.nav-tabs-justified>.active>a:hover{border-bottom-color:#fff}}.tab-content>.tab-pane{display:none}.tab-content>.active{display:block}.nav-tabs .dropdown-menu{margin-top:-1px;border-top-left-radius:0;border-top-right-radius:0}.navbar{position:relative;min-height:50px;margin-bottom:20px;border:1px solid transparent}@media (min-width:768px){.navbar{border-radius:4px}}@media (min-width:768px){.navbar-header{float:left}}.navbar-collapse{padding-right:15px;padding-left:15px;overflow-x:visible;border-top:1px solid transparent;-webkit-box-shadow:inset 0 1px 0 rgba(255,255,255,.1);box-shadow:inset 0 1px 0 rgba(255,255,255,.1);-webkit-overflow-scrolling:touch}.navbar-collapse.in{overflow-y:auto}@media (min-width:768px){.navbar-collapse{width:auto;border-top:0;-webkit-box-shadow:none;box-shadow:none}.navbar-collapse.collapse{display:block!important;height:auto!important;padding-bottom:0;overflow:visible!important}.navbar-collapse.in{overflow-y:visible}.navbar-fixed-bottom .navbar-collapse,.navbar-fixed-top .navbar-collapse,.navbar-static-top .navbar-collapse{padding-right:0;padding-left:0}}.navbar-fixed-bottom,.navbar-fixed-top{position:fixed;right:0;left:0;z-index:1030}.navbar-fixed-bottom .navbar-collapse,.navbar-fixed-top .navbar-collapse{max-height:340px}@media (max-device-width:480px) and (orientation:landscape){.navbar-fixed-bottom .navbar-collapse,.navbar-fixed-top .navbar-collapse{max-height:200px}}@media (min-width:768px){.navbar-fixed-bottom,.navbar-fixed-top{border-radius:0}}.navbar-fixed-top{top:0;border-width:0 0 1px}.navbar-fixed-bottom{bottom:0;margin-bottom:0;border-width:1px 0 0}.container-fluid>.navbar-collapse,.container-fluid>.navbar-header,.container>.navbar-collapse,.container>.navbar-header{margin-right:-15px;margin-left:-15px}@media (min-width:768px){.container-fluid>.navbar-collapse,.container-fluid>.navbar-header,.container>.navbar-collapse,.container>.navbar-header{margin-right:0;margin-left:0}}.navbar-static-top{z-index:1000;border-width:0 0 1px}@media (min-width:768px){.navbar-static-top{border-radius:0}}.navbar-brand{float:left;height:50px;padding:15px 15px;font-size:18px;line-height:20px}.navbar-brand:focus,.navbar-brand:hover{text-decoration:none}.navbar-brand>img{display:block}@media (min-width:768px){.navbar>.container .navbar-brand,.navbar>.container-fluid .navbar-brand{margin-left:-15px}}.navbar-toggle{position:relative;float:right;padding:9px 10px;margin-right:15px;margin-top:8px;margin-bottom:8px;background-color:transparent;background-image:none;border:1px solid transparent;border-radius:4px}.navbar-toggle:focus{outline:0}.navbar-toggle .icon-bar{display:block;width:22px;height:2px;border-radius:1px}.navbar-toggle .icon-bar+.icon-bar{margin-top:4px}@media (min-width:768px){.navbar-toggle{display:none}}.navbar-nav{margin:7.5px -15px}.navbar-nav>li>a{padding-top:10px;padding-bottom:10px;line-height:20px}@media (max-width:767px){.navbar-nav .open .dropdown-menu{position:static;float:none;width:auto;margin-top:0;background-color:transparent;border:0;-webkit-box-shadow:none;box-shadow:none}.navbar-nav .open .dropdown-menu .dropdown-header,.navbar-nav .open .dropdown-menu>li>a{padding:5px 15px 5px 25px}.navbar-nav .open .dropdown-menu>li>a{line-height:20px}.navbar-nav .open .dropdown-menu>li>a:focus,.navbar-nav .open .dropdown-menu>li>a:hover{background-image:none}}@media (min-width:768px){.navbar-nav{float:left;margin:0}.navbar-nav>li{float:left}.navbar-nav>li>a{padding-top:15px;padding-bottom:15px}}.navbar-form{padding:10px 15px;margin-right:-15px;margin-left:-15px;border-top:1px solid transparent;border-bottom:1px solid transparent;-webkit-box-shadow:inset 0 1px 0 rgba(255,255,255,.1),0 1px 0 rgba(255,255,255,.1);box-shadow:inset 0 1px 0 rgba(255,255,255,.1),0 1px 0 rgba(255,255,255,.1);margin-top:8px;margin-bottom:8px}@media (min-width:768px){.navbar-form .form-group{display:inline-block;margin-bottom:0;vertical-align:middle}.navbar-form .form-control{display:inline-block;width:auto;vertical-align:middle}.navbar-form .form-control-static{display:inline-block}.navbar-form .input-group{display:inline-table;vertical-align:middle}.navbar-form .input-group .form-control,.navbar-form .input-group .input-group-addon,.navbar-form .input-group .input-group-btn{width:auto}.navbar-form .input-group>.form-control{width:100%}.navbar-form .control-label{margin-bottom:0;vertical-align:middle}.navbar-form .checkbox,.navbar-form .radio{display:inline-block;margin-top:0;margin-bottom:0;vertical-align:middle}.navbar-form .checkbox label,.navbar-form .radio label{padding-left:0}.navbar-form .checkbox input[type=checkbox],.navbar-form .radio input[type=radio]{position:relative;margin-left:0}.navbar-form .has-feedback .form-control-feedback{top:0}}@media (max-width:767px){.navbar-form .form-group{margin-bottom:5px}.navbar-form .form-group:last-child{margin-bottom:0}}@media (min-width:768px){.navbar-form{width:auto;padding-top:0;padding-bottom:0;margin-right:0;margin-left:0;border:0;-webkit-box-shadow:none;box-shadow:none}}.navbar-nav>li>.dropdown-menu{margin-top:0;border-top-left-radius:0;border-top-right-radius:0}.navbar-fixed-bottom .navbar-nav>li>.dropdown-menu{margin-bottom:0;border-top-left-radius:4px;border-top-right-radius:4px;border-bottom-right-radius:0;border-bottom-left-radius:0}.navbar-btn{margin-top:8px;margin-bottom:8px}.navbar-btn.btn-sm{margin-top:10px;margin-bottom:10px}.navbar-btn.btn-xs{margin-top:14px;margin-bottom:14px}.navbar-text{margin-top:15px;margin-bottom:15px}@media (min-width:768px){.navbar-text{float:left;margin-right:15px;margin-left:15px}}@media (min-width:768px){.navbar-left{float:left!important}.navbar-right{float:right!important;margin-right:-15px}.navbar-right~.navbar-right{margin-right:0}}.navbar-default{background-color:#f8f8f8;border-color:#e7e7e7}.navbar-default .navbar-brand{color:#777}.navbar-default .navbar-brand:focus,.navbar-default .navbar-brand:hover{color:#5e5e5e;background-color:transparent}.navbar-default .navbar-text{color:#777}.navbar-default .navbar-nav>li>a{color:#777}.navbar-default .navbar-nav>li>a:focus,.navbar-default .navbar-nav>li>a:hover{color:#333;background-color:transparent}.navbar-default .navbar-nav>.active>a,.navbar-default .navbar-nav>.active>a:focus,.navbar-default .navbar-nav>.active>a:hover{color:#555;background-color:#e7e7e7}.navbar-default .navbar-nav>.disabled>a,.navbar-default .navbar-nav>.disabled>a:focus,.navbar-default .navbar-nav>.disabled>a:hover{color:#ccc;background-color:transparent}.navbar-default .navbar-nav>.open>a,.navbar-default .navbar-nav>.open>a:focus,.navbar-default .navbar-nav>.open>a:hover{color:#555;background-color:#e7e7e7}@media (max-width:767px){.navbar-default .navbar-nav .open .dropdown-menu>li>a{color:#777}.navbar-default .navbar-nav .open .dropdown-menu>li>a:focus,.navbar-default .navbar-nav .open .dropdown-menu>li>a:hover{color:#333;background-color:transparent}.navbar-default .navbar-nav .open .dropdown-menu>.active>a,.navbar-default .navbar-nav .open .dropdown-menu>.active>a:focus,.navbar-default .navbar-nav .open .dropdown-menu>.active>a:hover{color:#555;background-color:#e7e7e7}.navbar-default .navbar-nav .open .dropdown-menu>.disabled>a,.navbar-default .navbar-nav .open .dropdown-menu>.disabled>a:focus,.navbar-default .navbar-nav .open .dropdown-menu>.disabled>a:hover{color:#ccc;background-color:transparent}}.navbar-default .navbar-toggle{border-color:#ddd}.navbar-default .navbar-toggle:focus,.navbar-default .navbar-toggle:hover{background-color:#ddd}.navbar-default .navbar-toggle .icon-bar{background-color:#888}.navbar-default .navbar-collapse,.navbar-default .navbar-form{border-color:#e7e7e7}.navbar-default .navbar-link{color:#777}.navbar-default .navbar-link:hover{color:#333}.navbar-default .btn-link{color:#777}.navbar-default .btn-link:focus,.navbar-default .btn-link:hover{color:#333}.navbar-default .btn-link[disabled]:focus,.navbar-default .btn-link[disabled]:hover,fieldset[disabled] .navbar-default .btn-link:focus,fieldset[disabled] .navbar-default .btn-link:hover{color:#ccc}.navbar-inverse{background-color:#222;border-color:#080808}.navbar-inverse .navbar-brand{color:#9d9d9d}.navbar-inverse .navbar-brand:focus,.navbar-inverse .navbar-brand:hover{color:#fff;background-color:transparent}.navbar-inverse .navbar-text{color:#9d9d9d}.navbar-inverse .navbar-nav>li>a{color:#9d9d9d}.navbar-inverse .navbar-nav>li>a:focus,.navbar-inverse .navbar-nav>li>a:hover{color:#fff;background-color:transparent}.navbar-inverse .navbar-nav>.active>a,.navbar-inverse .navbar-nav>.active>a:focus,.navbar-inverse .navbar-nav>.active>a:hover{color:#fff;background-color:#080808}.navbar-inverse .navbar-nav>.disabled>a,.navbar-inverse .navbar-nav>.disabled>a:focus,.navbar-inverse .navbar-nav>.disabled>a:hover{color:#444;background-color:transparent}.navbar-inverse .navbar-nav>.open>a,.navbar-inverse .navbar-nav>.open>a:focus,.navbar-inverse .navbar-nav>.open>a:hover{color:#fff;background-color:#080808}@media (max-width:767px){.navbar-inverse .navbar-nav .open .dropdown-menu>.dropdown-header{border-color:#080808}.navbar-inverse .navbar-nav .open .dropdown-menu .divider{background-color:#080808}.navbar-inverse .navbar-nav .open .dropdown-menu>li>a{color:#9d9d9d}.navbar-inverse .navbar-nav .open .dropdown-menu>li>a:focus,.navbar-inverse .navbar-nav .open .dropdown-menu>li>a:hover{color:#fff;background-color:transparent}.navbar-inverse .navbar-nav .open .dropdown-menu>.active>a,.navbar-inverse .navbar-nav .open .dropdown-menu>.active>a:focus,.navbar-inverse .navbar-nav .open .dropdown-menu>.active>a:hover{color:#fff;background-color:#080808}.navbar-inverse .navbar-nav .open .dropdown-menu>.disabled>a,.navbar-inverse .navbar-nav .open .dropdown-menu>.disabled>a:focus,.navbar-inverse .navbar-nav .open .dropdown-menu>.disabled>a:hover{color:#444;background-color:transparent}}.navbar-inverse .navbar-toggle{border-color:#333}.navbar-inverse .navbar-toggle:focus,.navbar-inverse .navbar-toggle:hover{background-color:#333}.navbar-inverse .navbar-toggle .icon-bar{background-color:#fff}.navbar-inverse .navbar-collapse,.navbar-inverse .navbar-form{border-color:#101010}.navbar-inverse .navbar-link{color:#9d9d9d}.navbar-inverse .navbar-link:hover{color:#fff}.navbar-inverse .btn-link{color:#9d9d9d}.navbar-inverse .btn-link:focus,.navbar-inverse .btn-link:hover{color:#fff}.navbar-inverse .btn-link[disabled]:focus,.navbar-inverse .btn-link[disabled]:hover,fieldset[disabled] .navbar-inverse .btn-link:focus,fieldset[disabled] .navbar-inverse .btn-link:hover{color:#444}.breadcrumb{padding:8px 15px;margin-bottom:20px;list-style:none;background-color:#f5f5f5;border-radius:4px}.breadcrumb>li{display:inline-block}.breadcrumb>li+li:before{padding:0 5px;color:#ccc;content:"/\00a0"}.breadcrumb>.active{color:#777}.pagination{display:inline-block;padding-left:0;margin:20px 0;border-radius:4px}.pagination>li{display:inline}.pagination>li>a,.pagination>li>span{position:relative;float:left;padding:6px 12px;margin-left:-1px;line-height:1.42857143;color:#337ab7;text-decoration:none;background-color:#fff;border:1px solid #ddd}.pagination>li>a:focus,.pagination>li>a:hover,.pagination>li>span:focus,.pagination>li>span:hover{z-index:2;color:#23527c;background-color:#eee;border-color:#ddd}.pagination>li:first-child>a,.pagination>li:first-child>span{margin-left:0;border-top-left-radius:4px;border-bottom-left-radius:4px}.pagination>li:last-child>a,.pagination>li:last-child>span{border-top-right-radius:4px;border-bottom-right-radius:4px}.pagination>.active>a,.pagination>.active>a:focus,.pagination>.active>a:hover,.pagination>.active>span,.pagination>.active>span:focus,.pagination>.active>span:hover{z-index:3;color:#fff;cursor:default;background-color:#337ab7;border-color:#337ab7}.pagination>.disabled>a,.pagination>.disabled>a:focus,.pagination>.disabled>a:hover,.pagination>.disabled>span,.pagination>.disabled>span:focus,.pagination>.disabled>span:hover{color:#777;cursor:not-allowed;background-color:#fff;border-color:#ddd}.pagination-lg>li>a,.pagination-lg>li>span{padding:10px 16px;font-size:18px;line-height:1.3333333}.pagination-lg>li:first-child>a,.pagination-lg>li:first-child>span{border-top-left-radius:6px;border-bottom-left-radius:6px}.pagination-lg>li:last-child>a,.pagination-lg>li:last-child>span{border-top-right-radius:6px;border-bottom-right-radius:6px}.pagination-sm>li>a,.pagination-sm>li>span{padding:5px 10px;font-size:12px;line-height:1.5}.pagination-sm>li:first-child>a,.pagination-sm>li:first-child>span{border-top-left-radius:3px;border-bottom-left-radius:3px}.pagination-sm>li:last-child>a,.pagination-sm>li:last-child>span{border-top-right-radius:3px;border-bottom-right-radius:3px}.pager{padding-left:0;margin:20px 0;text-align:center;list-style:none}.pager li{display:inline}.pager li>a,.pager li>span{display:inline-block;padding:5px 14px;background-color:#fff;border:1px solid #ddd;border-radius:15px}.pager li>a:focus,.pager li>a:hover{text-decoration:none;background-color:#eee}.pager .next>a,.pager .next>span{float:right}.pager .previous>a,.pager .previous>span{float:left}.pager .disabled>a,.pager .disabled>a:focus,.pager .disabled>a:hover,.pager .disabled>span{color:#777;cursor:not-allowed;background-color:#fff}.label{display:inline;padding:.2em .6em .3em;font-size:75%;font-weight:700;line-height:1;color:#fff;text-align:center;white-space:nowrap;vertical-align:baseline;border-radius:.25em}a.label:focus,a.label:hover{color:#fff;text-decoration:none;cursor:pointer}.label:empty{display:none}.btn .label{position:relative;top:-1px}.label-default{background-color:#777}.label-default[href]:focus,.label-default[href]:hover{background-color:#5e5e5e}.label-primary{background-color:#337ab7}.label-primary[href]:focus,.label-primary[href]:hover{background-color:#286090}.label-success{background-color:#5cb85c}.label-success[href]:focus,.label-success[href]:hover{background-color:#449d44}.label-info{background-color:#5bc0de}.label-info[href]:focus,.label-info[href]:hover{background-color:#31b0d5}.label-warning{background-color:#f0ad4e}.label-warning[href]:focus,.label-warning[href]:hover{background-color:#ec971f}.label-danger{background-color:#d9534f}.label-danger[href]:focus,.label-danger[href]:hover{background-color:#c9302c}.badge{display:inline-block;min-width:10px;padding:3px 7px;font-size:12px;font-weight:700;line-height:1;color:#fff;text-align:center;white-space:nowrap;vertical-align:middle;background-color:#777;border-radius:10px}.badge:empty{display:none}.btn .badge{position:relative;top:-1px}.btn-group-xs>.btn .badge,.btn-xs .badge{top:0;padding:1px 5px}a.badge:focus,a.badge:hover{color:#fff;text-decoration:none;cursor:pointer}.list-group-item.active>.badge,.nav-pills>.active>a>.badge{color:#337ab7;background-color:#fff}.list-group-item>.badge{float:right}.list-group-item>.badge+.badge{margin-right:5px}.nav-pills>li>a>.badge{margin-left:3px}.jumbotron{padding-top:30px;padding-bottom:30px;margin-bottom:30px;color:inherit;background-color:#eee}.jumbotron .h1,.jumbotron h1{color:inherit}.jumbotron p{margin-bottom:15px;font-size:21px;font-weight:200}.jumbotron>hr{border-top-color:#d5d5d5}.container .jumbotron,.container-fluid .jumbotron{padding-right:15px;padding-left:15px;border-radius:6px}.jumbotron .container{max-width:100%}@media screen and (min-width:768px){.jumbotron{padding-top:48px;padding-bottom:48px}.container .jumbotron,.container-fluid .jumbotron{padding-right:60px;padding-left:60px}.jumbotron .h1,.jumbotron h1{font-size:63px}}.thumbnail{display:block;padding:4px;margin-bottom:20px;line-height:1.42857143;background-color:#fff;border:1px solid #ddd;border-radius:4px;-webkit-transition:border .2s ease-in-out;-o-transition:border .2s ease-in-out;transition:border .2s ease-in-out}.thumbnail a>img,.thumbnail>img{margin-right:auto;margin-left:auto}a.thumbnail.active,a.thumbnail:focus,a.thumbnail:hover{border-color:#337ab7}.thumbnail .caption{padding:9px;color:#333}.alert{padding:15px;margin-bottom:20px;border:1px solid transparent;border-radius:4px}.alert h4{margin-top:0;color:inherit}.alert .alert-link{font-weight:700}.alert>p,.alert>ul{margin-bottom:0}.alert>p+p{margin-top:5px}.alert-dismissable,.alert-dismissible{padding-right:35px}.alert-dismissable .close,.alert-dismissible .close{position:relative;top:-2px;right:-21px;color:inherit}.alert-success{color:#3c763d;background-color:#dff0d8;border-color:#d6e9c6}.alert-success hr{border-top-color:#c9e2b3}.alert-success .alert-link{color:#2b542c}.alert-info{color:#31708f;background-color:#d9edf7;border-color:#bce8f1}.alert-info hr{border-top-color:#a6e1ec}.alert-info .alert-link{color:#245269}.alert-warning{color:#8a6d3b;background-color:#fcf8e3;border-color:#faebcc}.alert-warning hr{border-top-color:#f7e1b5}.alert-warning .alert-link{color:#66512c}.alert-danger{color:#a94442;background-color:#f2dede;border-color:#ebccd1}.alert-danger hr{border-top-color:#e4b9c0}.alert-danger .alert-link{color:#843534}@-webkit-keyframes progress-bar-stripes{from{background-position:40px 0}to{background-position:0 0}}@-o-keyframes progress-bar-stripes{from{background-position:40px 0}to{background-position:0 0}}@keyframes progress-bar-stripes{from{background-position:40px 0}to{background-position:0 0}}.progress{height:20px;margin-bottom:20px;overflow:hidden;background-color:#f5f5f5;border-radius:4px;-webkit-box-shadow:inset 0 1px 2px rgba(0,0,0,.1);box-shadow:inset 0 1px 2px rgba(0,0,0,.1)}.progress-bar{float:left;width:0%;height:100%;font-size:12px;line-height:20px;color:#fff;text-align:center;background-color:#337ab7;-webkit-box-shadow:inset 0 -1px 0 rgba(0,0,0,.15);box-shadow:inset 0 -1px 0 rgba(0,0,0,.15);-webkit-transition:width .6s ease;-o-transition:width .6s ease;transition:width .6s ease}.progress-bar-striped,.progress-striped .progress-bar{background-image:-webkit-linear-gradient(45deg,rgba(255,255,255,.15) 25%,transparent 25%,transparent 50%,rgba(255,255,255,.15) 50%,rgba(255,255,255,.15) 75%,transparent 75%,transparent);background-image:-o-linear-gradient(45deg,rgba(255,255,255,.15) 25%,transparent 25%,transparent 50%,rgba(255,255,255,.15) 50%,rgba(255,255,255,.15) 75%,transparent 75%,transparent);background-image:linear-gradient(45deg,rgba(255,255,255,.15) 25%,transparent 25%,transparent 50%,rgba(255,255,255,.15) 50%,rgba(255,255,255,.15) 75%,transparent 75%,transparent);-webkit-background-size:40px 40px;background-size:40px 40px}.progress-bar.active,.progress.active .progress-bar{-webkit-animation:progress-bar-stripes 2s linear infinite;-o-animation:progress-bar-stripes 2s linear infinite;animation:progress-bar-stripes 2s linear infinite}.progress-bar-success{background-color:#5cb85c}.progress-striped .progress-bar-success{background-image:-webkit-linear-gradient(45deg,rgba(255,255,255,.15) 25%,transparent 25%,transparent 50%,rgba(255,255,255,.15) 50%,rgba(255,255,255,.15) 75%,transparent 75%,transparent);background-image:-o-linear-gradient(45deg,rgba(255,255,255,.15) 25%,transparent 25%,transparent 50%,rgba(255,255,255,.15) 50%,rgba(255,255,255,.15) 75%,transparent 75%,transparent);background-image:linear-gradient(45deg,rgba(255,255,255,.15) 25%,transparent 25%,transparent 50%,rgba(255,255,255,.15) 50%,rgba(255,255,255,.15) 75%,transparent 75%,transparent)}.progress-bar-info{background-color:#5bc0de}.progress-striped .progress-bar-info{background-image:-webkit-linear-gradient(45deg,rgba(255,255,255,.15) 25%,transparent 25%,transparent 50%,rgba(255,255,255,.15) 50%,rgba(255,255,255,.15) 75%,transparent 75%,transparent);background-image:-o-linear-gradient(45deg,rgba(255,255,255,.15) 25%,transparent 25%,transparent 50%,rgba(255,255,255,.15) 50%,rgba(255,255,255,.15) 75%,transparent 75%,transparent);background-image:linear-gradient(45deg,rgba(255,255,255,.15) 25%,transparent 25%,transparent 50%,rgba(255,255,255,.15) 50%,rgba(255,255,255,.15) 75%,transparent 75%,transparent)}.progress-bar-warning{background-color:#f0ad4e}.progress-striped .progress-bar-warning{background-image:-webkit-linear-gradient(45deg,rgba(255,255,255,.15) 25%,transparent 25%,transparent 50%,rgba(255,255,255,.15) 50%,rgba(255,255,255,.15) 75%,transparent 75%,transparent);background-image:-o-linear-gradient(45deg,rgba(255,255,255,.15) 25%,transparent 25%,transparent 50%,rgba(255,255,255,.15) 50%,rgba(255,255,255,.15) 75%,transparent 75%,transparent);background-image:linear-gradient(45deg,rgba(255,255,255,.15) 25%,transparent 25%,transparent 50%,rgba(255,255,255,.15) 50%,rgba(255,255,255,.15) 75%,transparent 75%,transparent)}.progress-bar-danger{background-color:#d9534f}.progress-striped .progress-bar-danger{background-image:-webkit-linear-gradient(45deg,rgba(255,255,255,.15) 25%,transparent 25%,transparent 50%,rgba(255,255,255,.15) 50%,rgba(255,255,255,.15) 75%,transparent 75%,transparent);background-image:-o-linear-gradient(45deg,rgba(255,255,255,.15) 25%,transparent 25%,transparent 50%,rgba(255,255,255,.15) 50%,rgba(255,255,255,.15) 75%,transparent 75%,transparent);background-image:linear-gradient(45deg,rgba(255,255,255,.15) 25%,transparent 25%,transparent 50%,rgba(255,255,255,.15) 50%,rgba(255,255,255,.15) 75%,transparent 75%,transparent)}.media{margin-top:15px}.media:first-child{margin-top:0}.media,.media-body{overflow:hidden;zoom:1}.media-body{width:10000px}.media-object{display:block}.media-object.img-thumbnail{max-width:none}.media-right,.media>.pull-right{padding-left:10px}.media-left,.media>.pull-left{padding-right:10px}.media-body,.media-left,.media-right{display:table-cell;vertical-align:top}.media-middle{vertical-align:middle}.media-bottom{vertical-align:bottom}.media-heading{margin-top:0;margin-bottom:5px}.media-list{padding-left:0;list-style:none}.list-group{padding-left:0;margin-bottom:20px}.list-group-item{position:relative;display:block;padding:10px 15px;margin-bottom:-1px;background-color:#fff;border:1px solid #ddd}.list-group-item:first-child{border-top-left-radius:4px;border-top-right-radius:4px}.list-group-item:last-child{margin-bottom:0;border-bottom-right-radius:4px;border-bottom-left-radius:4px}.list-group-item.disabled,.list-group-item.disabled:focus,.list-group-item.disabled:hover{color:#777;cursor:not-allowed;background-color:#eee}.list-group-item.disabled .list-group-item-heading,.list-group-item.disabled:focus .list-group-item-heading,.list-group-item.disabled:hover .list-group-item-heading{color:inherit}.list-group-item.disabled .list-group-item-text,.list-group-item.disabled:focus .list-group-item-text,.list-group-item.disabled:hover .list-group-item-text{color:#777}.list-group-item.active,.list-group-item.active:focus,.list-group-item.active:hover{z-index:2;color:#fff;background-color:#337ab7;border-color:#337ab7}.list-group-item.active .list-group-item-heading,.list-group-item.active .list-group-item-heading>.small,.list-group-item.active .list-group-item-heading>small,.list-group-item.active:focus .list-group-item-heading,.list-group-item.active:focus .list-group-item-heading>.small,.list-group-item.active:focus .list-group-item-heading>small,.list-group-item.active:hover .list-group-item-heading,.list-group-item.active:hover .list-group-item-heading>.small,.list-group-item.active:hover .list-group-item-heading>small{color:inherit}.list-group-item.active .list-group-item-text,.list-group-item.active:focus .list-group-item-text,.list-group-item.active:hover .list-group-item-text{color:#c7ddef}a.list-group-item,button.list-group-item{color:#555}a.list-group-item .list-group-item-heading,button.list-group-item .list-group-item-heading{color:#333}a.list-group-item:focus,a.list-group-item:hover,button.list-group-item:focus,button.list-group-item:hover{color:#555;text-decoration:none;background-color:#f5f5f5}button.list-group-item{width:100%;text-align:left}.list-group-item-success{color:#3c763d;background-color:#dff0d8}a.list-group-item-success,button.list-group-item-success{color:#3c763d}a.list-group-item-success .list-group-item-heading,button.list-group-item-success .list-group-item-heading{color:inherit}a.list-group-item-success:focus,a.list-group-item-success:hover,button.list-group-item-success:focus,button.list-group-item-success:hover{color:#3c763d;background-color:#d0e9c6}a.list-group-item-success.active,a.list-group-item-success.active:focus,a.list-group-item-success.active:hover,button.list-group-item-success.active,button.list-group-item-success.active:focus,button.list-group-item-success.active:hover{color:#fff;background-color:#3c763d;border-color:#3c763d}.list-group-item-info{color:#31708f;background-color:#d9edf7}a.list-group-item-info,button.list-group-item-info{color:#31708f}a.list-group-item-info .list-group-item-heading,button.list-group-item-info .list-group-item-heading{color:inherit}a.list-group-item-info:focus,a.list-group-item-info:hover,button.list-group-item-info:focus,button.list-group-item-info:hover{color:#31708f;background-color:#c4e3f3}a.list-group-item-info.active,a.list-group-item-info.active:focus,a.list-group-item-info.active:hover,button.list-group-item-info.active,button.list-group-item-info.active:focus,button.list-group-item-info.active:hover{color:#fff;background-color:#31708f;border-color:#31708f}.list-group-item-warning{color:#8a6d3b;background-color:#fcf8e3}a.list-group-item-warning,button.list-group-item-warning{color:#8a6d3b}a.list-group-item-warning .list-group-item-heading,button.list-group-item-warning .list-group-item-heading{color:inherit}a.list-group-item-warning:focus,a.list-group-item-warning:hover,button.list-group-item-warning:focus,button.list-group-item-warning:hover{color:#8a6d3b;background-color:#faf2cc}a.list-group-item-warning.active,a.list-group-item-warning.active:focus,a.list-group-item-warning.active:hover,button.list-group-item-warning.active,button.list-group-item-warning.active:focus,button.list-group-item-warning.active:hover{color:#fff;background-color:#8a6d3b;border-color:#8a6d3b}.list-group-item-danger{color:#a94442;background-color:#f2dede}a.list-group-item-danger,button.list-group-item-danger{color:#a94442}a.list-group-item-danger .list-group-item-heading,button.list-group-item-danger .list-group-item-heading{color:inherit}a.list-group-item-danger:focus,a.list-group-item-danger:hover,button.list-group-item-danger:focus,button.list-group-item-danger:hover{color:#a94442;background-color:#ebcccc}a.list-group-item-danger.active,a.list-group-item-danger.active:focus,a.list-group-item-danger.active:hover,button.list-group-item-danger.active,button.list-group-item-danger.active:focus,button.list-group-item-danger.active:hover{color:#fff;background-color:#a94442;border-color:#a94442}.list-group-item-heading{margin-top:0;margin-bottom:5px}.list-group-item-text{margin-bottom:0;line-height:1.3}.panel{margin-bottom:20px;background-color:#fff;border:1px solid transparent;border-radius:4px;-webkit-box-shadow:0 1px 1px rgba(0,0,0,.05);box-shadow:0 1px 1px rgba(0,0,0,.05)}.panel-body{padding:15px}.panel-heading{padding:10px 15px;border-bottom:1px solid transparent;border-top-left-radius:3px;border-top-right-radius:3px}.panel-heading>.dropdown .dropdown-toggle{color:inherit}.panel-title{margin-top:0;margin-bottom:0;font-size:16px;color:inherit}.panel-title>.small,.panel-title>.small>a,.panel-title>a,.panel-title>small,.panel-title>small>a{color:inherit}.panel-footer{padding:10px 15px;background-color:#f5f5f5;border-top:1px solid #ddd;border-bottom-right-radius:3px;border-bottom-left-radius:3px}.panel>.list-group,.panel>.panel-collapse>.list-group{margin-bottom:0}.panel>.list-group .list-group-item,.panel>.panel-collapse>.list-group .list-group-item{border-width:1px 0;border-radius:0}.panel>.list-group:first-child .list-group-item:first-child,.panel>.panel-collapse>.list-group:first-child .list-group-item:first-child{border-top:0;border-top-left-radius:3px;border-top-right-radius:3px}.panel>.list-group:last-child .list-group-item:last-child,.panel>.panel-collapse>.list-group:last-child .list-group-item:last-child{border-bottom:0;border-bottom-right-radius:3px;border-bottom-left-radius:3px}.panel>.panel-heading+.panel-collapse>.list-group .list-group-item:first-child{border-top-left-radius:0;border-top-right-radius:0}.panel-heading+.list-group .list-group-item:first-child{border-top-width:0}.list-group+.panel-footer{border-top-width:0}.panel>.panel-collapse>.table,.panel>.table,.panel>.table-responsive>.table{margin-bottom:0}.panel>.panel-collapse>.table caption,.panel>.table caption,.panel>.table-responsive>.table caption{padding-right:15px;padding-left:15px}.panel>.table-responsive:first-child>.table:first-child,.panel>.table:first-child{border-top-left-radius:3px;border-top-right-radius:3px}.panel>.table-responsive:first-child>.table:first-child>tbody:first-child>tr:first-child,.panel>.table-responsive:first-child>.table:first-child>thead:first-child>tr:first-child,.panel>.table:first-child>tbody:first-child>tr:first-child,.panel>.table:first-child>thead:first-child>tr:first-child{border-top-left-radius:3px;border-top-right-radius:3px}.panel>.table-responsive:first-child>.table:first-child>tbody:first-child>tr:first-child td:first-child,.panel>.table-responsive:first-child>.table:first-child>tbody:first-child>tr:first-child th:first-child,.panel>.table-responsive:first-child>.table:first-child>thead:first-child>tr:first-child td:first-child,.panel>.table-responsive:first-child>.table:first-child>thead:first-child>tr:first-child th:first-child,.panel>.table:first-child>tbody:first-child>tr:first-child td:first-child,.panel>.table:first-child>tbody:first-child>tr:first-child th:first-child,.panel>.table:first-child>thead:first-child>tr:first-child td:first-child,.panel>.table:first-child>thead:first-child>tr:first-child th:first-child{border-top-left-radius:3px}.panel>.table-responsive:first-child>.table:first-child>tbody:first-child>tr:first-child td:last-child,.panel>.table-responsive:first-child>.table:first-child>tbody:first-child>tr:first-child th:last-child,.panel>.table-responsive:first-child>.table:first-child>thead:first-child>tr:first-child td:last-child,.panel>.table-responsive:first-child>.table:first-child>thead:first-child>tr:first-child th:last-child,.panel>.table:first-child>tbody:first-child>tr:first-child td:last-child,.panel>.table:first-child>tbody:first-child>tr:first-child th:last-child,.panel>.table:first-child>thead:first-child>tr:first-child td:last-child,.panel>.table:first-child>thead:first-child>tr:first-child th:last-child{border-top-right-radius:3px}.panel>.table-responsive:last-child>.table:last-child,.panel>.table:last-child{border-bottom-right-radius:3px;border-bottom-left-radius:3px}.panel>.table-responsive:last-child>.table:last-child>tbody:last-child>tr:last-child,.panel>.table-responsive:last-child>.table:last-child>tfoot:last-child>tr:last-child,.panel>.table:last-child>tbody:last-child>tr:last-child,.panel>.table:last-child>tfoot:last-child>tr:last-child{border-bottom-right-radius:3px;border-bottom-left-radius:3px}.panel>.table-responsive:last-child>.table:last-child>tbody:last-child>tr:last-child td:first-child,.panel>.table-responsive:last-child>.table:last-child>tbody:last-child>tr:last-child th:first-child,.panel>.table-responsive:last-child>.table:last-child>tfoot:last-child>tr:last-child td:first-child,.panel>.table-responsive:last-child>.table:last-child>tfoot:last-child>tr:last-child th:first-child,.panel>.table:last-child>tbody:last-child>tr:last-child td:first-child,.panel>.table:last-child>tbody:last-child>tr:last-child th:first-child,.panel>.table:last-child>tfoot:last-child>tr:last-child td:first-child,.panel>.table:last-child>tfoot:last-child>tr:last-child th:first-child{border-bottom-left-radius:3px}.panel>.table-responsive:last-child>.table:last-child>tbody:last-child>tr:last-child td:last-child,.panel>.table-responsive:last-child>.table:last-child>tbody:last-child>tr:last-child th:last-child,.panel>.table-responsive:last-child>.table:last-child>tfoot:last-child>tr:last-child td:last-child,.panel>.table-responsive:last-child>.table:last-child>tfoot:last-child>tr:last-child th:last-child,.panel>.table:last-child>tbody:last-child>tr:last-child td:last-child,.panel>.table:last-child>tbody:last-child>tr:last-child th:last-child,.panel>.table:last-child>tfoot:last-child>tr:last-child td:last-child,.panel>.table:last-child>tfoot:last-child>tr:last-child th:last-child{border-bottom-right-radius:3px}.panel>.panel-body+.table,.panel>.panel-body+.table-responsive,.panel>.table+.panel-body,.panel>.table-responsive+.panel-body{border-top:1px solid #ddd}.panel>.table>tbody:first-child>tr:first-child td,.panel>.table>tbody:first-child>tr:first-child th{border-top:0}.panel>.table-bordered,.panel>.table-responsive>.table-bordered{border:0}.panel>.table-bordered>tbody>tr>td:first-child,.panel>.table-bordered>tbody>tr>th:first-child,.panel>.table-bordered>tfoot>tr>td:first-child,.panel>.table-bordered>tfoot>tr>th:first-child,.panel>.table-bordered>thead>tr>td:first-child,.panel>.table-bordered>thead>tr>th:first-child,.panel>.table-responsive>.table-bordered>tbody>tr>td:first-child,.panel>.table-responsive>.table-bordered>tbody>tr>th:first-child,.panel>.table-responsive>.table-bordered>tfoot>tr>td:first-child,.panel>.table-responsive>.table-bordered>tfoot>tr>th:first-child,.panel>.table-responsive>.table-bordered>thead>tr>td:first-child,.panel>.table-responsive>.table-bordered>thead>tr>th:first-child{border-left:0}.panel>.table-bordered>tbody>tr>td:last-child,.panel>.table-bordered>tbody>tr>th:last-child,.panel>.table-bordered>tfoot>tr>td:last-child,.panel>.table-bordered>tfoot>tr>th:last-child,.panel>.table-bordered>thead>tr>td:last-child,.panel>.table-bordered>thead>tr>th:last-child,.panel>.table-responsive>.table-bordered>tbody>tr>td:last-child,.panel>.table-responsive>.table-bordered>tbody>tr>th:last-child,.panel>.table-responsive>.table-bordered>tfoot>tr>td:last-child,.panel>.table-responsive>.table-bordered>tfoot>tr>th:last-child,.panel>.table-responsive>.table-bordered>thead>tr>td:last-child,.panel>.table-responsive>.table-bordered>thead>tr>th:last-child{border-right:0}.panel>.table-bordered>tbody>tr:first-child>td,.panel>.table-bordered>tbody>tr:first-child>th,.panel>.table-bordered>thead>tr:first-child>td,.panel>.table-bordered>thead>tr:first-child>th,.panel>.table-responsive>.table-bordered>tbody>tr:first-child>td,.panel>.table-responsive>.table-bordered>tbody>tr:first-child>th,.panel>.table-responsive>.table-bordered>thead>tr:first-child>td,.panel>.table-responsive>.table-bordered>thead>tr:first-child>th{border-bottom:0}.panel>.table-bordered>tbody>tr:last-child>td,.panel>.table-bordered>tbody>tr:last-child>th,.panel>.table-bordered>tfoot>tr:last-child>td,.panel>.table-bordered>tfoot>tr:last-child>th,.panel>.table-responsive>.table-bordered>tbody>tr:last-child>td,.panel>.table-responsive>.table-bordered>tbody>tr:last-child>th,.panel>.table-responsive>.table-bordered>tfoot>tr:last-child>td,.panel>.table-responsive>.table-bordered>tfoot>tr:last-child>th{border-bottom:0}.panel>.table-responsive{margin-bottom:0;border:0}.panel-group{margin-bottom:20px}.panel-group .panel{margin-bottom:0;border-radius:4px}.panel-group .panel+.panel{margin-top:5px}.panel-group .panel-heading{border-bottom:0}.panel-group .panel-heading+.panel-collapse>.list-group,.panel-group .panel-heading+.panel-collapse>.panel-body{border-top:1px solid #ddd}.panel-group .panel-footer{border-top:0}.panel-group .panel-footer+.panel-collapse .panel-body{border-bottom:1px solid #ddd}.panel-default{border-color:#ddd}.panel-default>.panel-heading{color:#333;background-color:#f5f5f5;border-color:#ddd}.panel-default>.panel-heading+.panel-collapse>.panel-body{border-top-color:#ddd}.panel-default>.panel-heading .badge{color:#f5f5f5;background-color:#333}.panel-default>.panel-footer+.panel-collapse>.panel-body{border-bottom-color:#ddd}.panel-primary{border-color:#337ab7}.panel-primary>.panel-heading{color:#fff;background-color:#337ab7;border-color:#337ab7}.panel-primary>.panel-heading+.panel-collapse>.panel-body{border-top-color:#337ab7}.panel-primary>.panel-heading .badge{color:#337ab7;background-color:#fff}.panel-primary>.panel-footer+.panel-collapse>.panel-body{border-bottom-color:#337ab7}.panel-success{border-color:#d6e9c6}.panel-success>.panel-heading{color:#3c763d;background-color:#dff0d8;border-color:#d6e9c6}.panel-success>.panel-heading+.panel-collapse>.panel-body{border-top-color:#d6e9c6}.panel-success>.panel-heading .badge{color:#dff0d8;background-color:#3c763d}.panel-success>.panel-footer+.panel-collapse>.panel-body{border-bottom-color:#d6e9c6}.panel-info{border-color:#bce8f1}.panel-info>.panel-heading{color:#31708f;background-color:#d9edf7;border-color:#bce8f1}.panel-info>.panel-heading+.panel-collapse>.panel-body{border-top-color:#bce8f1}.panel-info>.panel-heading .badge{color:#d9edf7;background-color:#31708f}.panel-info>.panel-footer+.panel-collapse>.panel-body{border-bottom-color:#bce8f1}.panel-warning{border-color:#faebcc}.panel-warning>.panel-heading{color:#8a6d3b;background-color:#fcf8e3;border-color:#faebcc}.panel-warning>.panel-heading+.panel-collapse>.panel-body{border-top-color:#faebcc}.panel-warning>.panel-heading .badge{color:#fcf8e3;background-color:#8a6d3b}.panel-warning>.panel-footer+.panel-collapse>.panel-body{border-bottom-color:#faebcc}.panel-danger{border-color:#ebccd1}.panel-danger>.panel-heading{color:#a94442;background-color:#f2dede;border-color:#ebccd1}.panel-danger>.panel-heading+.panel-collapse>.panel-body{border-top-color:#ebccd1}.panel-danger>.panel-heading .badge{color:#f2dede;background-color:#a94442}.panel-danger>.panel-footer+.panel-collapse>.panel-body{border-bottom-color:#ebccd1}.embed-responsive{position:relative;display:block;height:0;padding:0;overflow:hidden}.embed-responsive .embed-responsive-item,.embed-responsive embed,.embed-responsive iframe,.embed-responsive object,.embed-responsive video{position:absolute;top:0;bottom:0;left:0;width:100%;height:100%;border:0}.embed-responsive-16by9{padding-bottom:56.25%}.embed-responsive-4by3{padding-bottom:75%}.well{min-height:20px;padding:19px;margin-bottom:20px;background-color:#f5f5f5;border:1px solid #e3e3e3;border-radius:4px;-webkit-box-shadow:inset 0 1px 1px rgba(0,0,0,.05);box-shadow:inset 0 1px 1px rgba(0,0,0,.05)}.well blockquote{border-color:#ddd;border-color:rgba(0,0,0,.15)}.well-lg{padding:24px;border-radius:6px}.well-sm{padding:9px;border-radius:3px}.close{float:right;font-size:21px;font-weight:700;line-height:1;color:#000;text-shadow:0 1px 0 #fff;filter:alpha(opacity=20);opacity:.2}.close:focus,.close:hover{color:#000;text-decoration:none;cursor:pointer;filter:alpha(opacity=50);opacity:.5}button.close{padding:0;cursor:pointer;background:0 0;border:0;-webkit-appearance:none;-moz-appearance:none;appearance:none}.modal-open{overflow:hidden}.modal{position:fixed;top:0;right:0;bottom:0;left:0;z-index:1050;display:none;overflow:hidden;-webkit-overflow-scrolling:touch;outline:0}.modal.fade .modal-dialog{-webkit-transform:translate(0,-25%);-ms-transform:translate(0,-25%);-o-transform:translate(0,-25%);transform:translate(0,-25%);-webkit-transition:-webkit-transform .3s ease-out;-o-transition:-o-transform .3s ease-out;transition:-webkit-transform .3s ease-out;transition:transform .3s ease-out;transition:transform .3s ease-out,-webkit-transform .3s ease-out,-o-transform .3s ease-out}.modal.in .modal-dialog{-webkit-transform:translate(0,0);-ms-transform:translate(0,0);-o-transform:translate(0,0);transform:translate(0,0)}.modal-open .modal{overflow-x:hidden;overflow-y:auto}.modal-dialog{position:relative;width:auto;margin:10px}.modal-content{position:relative;background-color:#fff;background-clip:padding-box;border:1px solid #999;border:1px solid rgba(0,0,0,.2);border-radius:6px;-webkit-box-shadow:0 3px 9px rgba(0,0,0,.5);box-shadow:0 3px 9px rgba(0,0,0,.5);outline:0}.modal-backdrop{position:fixed;top:0;right:0;bottom:0;left:0;z-index:1040;background-color:#000}.modal-backdrop.fade{filter:alpha(opacity=0);opacity:0}.modal-backdrop.in{filter:alpha(opacity=50);opacity:.5}.modal-header{padding:15px;border-bottom:1px solid #e5e5e5}.modal-header .close{margin-top:-2px}.modal-title{margin:0;line-height:1.42857143}.modal-body{position:relative;padding:15px}.modal-footer{padding:15px;text-align:right;border-top:1px solid #e5e5e5}.modal-footer .btn+.btn{margin-bottom:0;margin-left:5px}.modal-footer .btn-group .btn+.btn{margin-left:-1px}.modal-footer .btn-block+.btn-block{margin-left:0}.modal-scrollbar-measure{position:absolute;top:-9999px;width:50px;height:50px;overflow:scroll}@media (min-width:768px){.modal-dialog{width:600px;margin:30px auto}.modal-content{-webkit-box-shadow:0 5px 15px rgba(0,0,0,.5);box-shadow:0 5px 15px rgba(0,0,0,.5)}.modal-sm{width:300px}}@media (min-width:992px){.modal-lg{width:900px}}.tooltip{position:absolute;z-index:1070;display:block;font-family:"Helvetica Neue",Helvetica,Arial,sans-serif;font-style:normal;font-weight:400;line-height:1.42857143;line-break:auto;text-align:left;text-align:start;text-decoration:none;text-shadow:none;text-transform:none;letter-spacing:normal;word-break:normal;word-spacing:normal;word-wrap:normal;white-space:normal;font-size:12px;filter:alpha(opacity=0);opacity:0}.tooltip.in{filter:alpha(opacity=90);opacity:.9}.tooltip.top{padding:5px 0;margin-top:-3px}.tooltip.right{padding:0 5px;margin-left:3px}.tooltip.bottom{padding:5px 0;margin-top:3px}.tooltip.left{padding:0 5px;margin-left:-3px}.tooltip.top .tooltip-arrow{bottom:0;left:50%;margin-left:-5px;border-width:5px 5px 0;border-top-color:#000}.tooltip.top-left .tooltip-arrow{right:5px;bottom:0;margin-bottom:-5px;border-width:5px 5px 0;border-top-color:#000}.tooltip.top-right .tooltip-arrow{bottom:0;left:5px;margin-bottom:-5px;border-width:5px 5px 0;border-top-color:#000}.tooltip.right .tooltip-arrow{top:50%;left:0;margin-top:-5px;border-width:5px 5px 5px 0;border-right-color:#000}.tooltip.left .tooltip-arrow{top:50%;right:0;margin-top:-5px;border-width:5px 0 5px 5px;border-left-color:#000}.tooltip.bottom .tooltip-arrow{top:0;left:50%;margin-left:-5px;border-width:0 5px 5px;border-bottom-color:#000}.tooltip.bottom-left .tooltip-arrow{top:0;right:5px;margin-top:-5px;border-width:0 5px 5px;border-bottom-color:#000}.tooltip.bottom-right .tooltip-arrow{top:0;left:5px;margin-top:-5px;border-width:0 5px 5px;border-bottom-color:#000}.tooltip-inner{max-width:200px;padding:3px 8px;color:#fff;text-align:center;background-color:#000;border-radius:4px}.tooltip-arrow{position:absolute;width:0;height:0;border-color:transparent;border-style:solid}.popover{position:absolute;top:0;left:0;z-index:1060;display:none;max-width:276px;padding:1px;font-family:"Helvetica Neue",Helvetica,Arial,sans-serif;font-style:normal;font-weight:400;line-height:1.42857143;line-break:auto;text-align:left;text-align:start;text-decoration:none;text-shadow:none;text-transform:none;letter-spacing:normal;word-break:normal;word-spacing:normal;word-wrap:normal;white-space:normal;font-size:14px;background-color:#fff;background-clip:padding-box;border:1px solid #ccc;border:1px solid rgba(0,0,0,.2);border-radius:6px;-webkit-box-shadow:0 5px 10px rgba(0,0,0,.2);box-shadow:0 5px 10px rgba(0,0,0,.2)}.popover.top{margin-top:-10px}.popover.right{margin-left:10px}.popover.bottom{margin-top:10px}.popover.left{margin-left:-10px}.popover>.arrow{border-width:11px}.popover>.arrow,.popover>.arrow:after{position:absolute;display:block;width:0;height:0;border-color:transparent;border-style:solid}.popover>.arrow:after{content:"";border-width:10px}.popover.top>.arrow{bottom:-11px;left:50%;margin-left:-11px;border-top-color:#999;border-top-color:rgba(0,0,0,.25);border-bottom-width:0}.popover.top>.arrow:after{bottom:1px;margin-left:-10px;content:" ";border-top-color:#fff;border-bottom-width:0}.popover.right>.arrow{top:50%;left:-11px;margin-top:-11px;border-right-color:#999;border-right-color:rgba(0,0,0,.25);border-left-width:0}.popover.right>.arrow:after{bottom:-10px;left:1px;content:" ";border-right-color:#fff;border-left-width:0}.popover.bottom>.arrow{top:-11px;left:50%;margin-left:-11px;border-top-width:0;border-bottom-color:#999;border-bottom-color:rgba(0,0,0,.25)}.popover.bottom>.arrow:after{top:1px;margin-left:-10px;content:" ";border-top-width:0;border-bottom-color:#fff}.popover.left>.arrow{top:50%;right:-11px;margin-top:-11px;border-right-width:0;border-left-color:#999;border-left-color:rgba(0,0,0,.25)}.popover.left>.arrow:after{right:1px;bottom:-10px;content:" ";border-right-width:0;border-left-color:#fff}.popover-title{padding:8px 14px;margin:0;font-size:14px;background-color:#f7f7f7;border-bottom:1px solid #ebebeb;border-radius:5px 5px 0 0}.popover-content{padding:9px 14px}.carousel{position:relative}.carousel-inner{position:relative;width:100%;overflow:hidden}.carousel-inner>.item{position:relative;display:none;-webkit-transition:.6s ease-in-out left;-o-transition:.6s ease-in-out left;transition:.6s ease-in-out left}.carousel-inner>.item>a>img,.carousel-inner>.item>img{line-height:1}@media all and (transform-3d),(-webkit-transform-3d){.carousel-inner>.item{-webkit-transition:-webkit-transform .6s ease-in-out;-o-transition:-o-transform .6s ease-in-out;transition:-webkit-transform .6s ease-in-out;transition:transform .6s ease-in-out;transition:transform .6s ease-in-out,-webkit-transform .6s ease-in-out,-o-transform .6s ease-in-out;-webkit-backface-visibility:hidden;backface-visibility:hidden;-webkit-perspective:1000px;perspective:1000px}.carousel-inner>.item.active.right,.carousel-inner>.item.next{-webkit-transform:translate3d(100%,0,0);transform:translate3d(100%,0,0);left:0}.carousel-inner>.item.active.left,.carousel-inner>.item.prev{-webkit-transform:translate3d(-100%,0,0);transform:translate3d(-100%,0,0);left:0}.carousel-inner>.item.active,.carousel-inner>.item.next.left,.carousel-inner>.item.prev.right{-webkit-transform:translate3d(0,0,0);transform:translate3d(0,0,0);left:0}}.carousel-inner>.active,.carousel-inner>.next,.carousel-inner>.prev{display:block}.carousel-inner>.active{left:0}.carousel-inner>.next,.carousel-inner>.prev{position:absolute;top:0;width:100%}.carousel-inner>.next{left:100%}.carousel-inner>.prev{left:-100%}.carousel-inner>.next.left,.carousel-inner>.prev.right{left:0}.carousel-inner>.active.left{left:-100%}.carousel-inner>.active.right{left:100%}.carousel-control{position:absolute;top:0;bottom:0;left:0;width:15%;font-size:20px;color:#fff;text-align:center;text-shadow:0 1px 2px rgba(0,0,0,.6);background-color:rgba(0,0,0,0);filter:alpha(opacity=50);opacity:.5}.carousel-control.left{background-image:-webkit-linear-gradient(left,rgba(0,0,0,.5) 0,rgba(0,0,0,.0001) 100%);background-image:-o-linear-gradient(left,rgba(0,0,0,.5) 0,rgba(0,0,0,.0001) 100%);background-image:-webkit-gradient(linear,left top,right top,from(rgba(0,0,0,.5)),to(rgba(0,0,0,.0001)));background-image:linear-gradient(to right,rgba(0,0,0,.5) 0,rgba(0,0,0,.0001) 100%);filter:progid:DXImageTransform.Microsoft.gradient(startColorstr='#80000000', endColorstr='#00000000', GradientType=1);background-repeat:repeat-x}.carousel-control.right{right:0;left:auto;background-image:-webkit-linear-gradient(left,rgba(0,0,0,.0001) 0,rgba(0,0,0,.5) 100%);background-image:-o-linear-gradient(left,rgba(0,0,0,.0001) 0,rgba(0,0,0,.5) 100%);background-image:-webkit-gradient(linear,left top,right top,from(rgba(0,0,0,.0001)),to(rgba(0,0,0,.5)));background-image:linear-gradient(to right,rgba(0,0,0,.0001) 0,rgba(0,0,0,.5) 100%);filter:progid:DXImageTransform.Microsoft.gradient(startColorstr='#00000000', endColorstr='#80000000', GradientType=1);background-repeat:repeat-x}.carousel-control:focus,.carousel-control:hover{color:#fff;text-decoration:none;outline:0;filter:alpha(opacity=90);opacity:.9}.carousel-control .glyphicon-chevron-left,.carousel-control .glyphicon-chevron-right,.carousel-control .icon-next,.carousel-control .icon-prev{position:absolute;top:50%;z-index:5;display:inline-block;margin-top:-10px}.carousel-control .glyphicon-chevron-left,.carousel-control .icon-prev{left:50%;margin-left:-10px}.carousel-control .glyphicon-chevron-right,.carousel-control .icon-next{right:50%;margin-right:-10px}.carousel-control .icon-next,.carousel-control .icon-prev{width:20px;height:20px;font-family:serif;line-height:1}.carousel-control .icon-prev:before{content:"\2039"}.carousel-control .icon-next:before{content:"\203a"}.carousel-indicators{position:absolute;bottom:10px;left:50%;z-index:15;width:60%;padding-left:0;margin-left:-30%;text-align:center;list-style:none}.carousel-indicators li{display:inline-block;width:10px;height:10px;margin:1px;text-indent:-999px;cursor:pointer;background-color:#000\9;background-color:rgba(0,0,0,0);border:1px solid #fff;border-radius:10px}.carousel-indicators .active{width:12px;height:12px;margin:0;background-color:#fff}.carousel-caption{position:absolute;right:15%;bottom:20px;left:15%;z-index:10;padding-top:20px;padding-bottom:20px;color:#fff;text-align:center;text-shadow:0 1px 2px rgba(0,0,0,.6)}.carousel-caption .btn{text-shadow:none}@media screen and (min-width:768px){.carousel-control .glyphicon-chevron-left,.carousel-control .glyphicon-chevron-right,.carousel-control .icon-next,.carousel-control .icon-prev{width:30px;height:30px;margin-top:-10px;font-size:30px}.carousel-control .glyphicon-chevron-left,.carousel-control .icon-prev{margin-left:-10px}.carousel-control .glyphicon-chevron-right,.carousel-control .icon-next{margin-right:-10px}.carousel-caption{right:20%;left:20%;padding-bottom:30px}.carousel-indicators{bottom:20px}}.btn-group-vertical>.btn-group:after,.btn-group-vertical>.btn-group:before,.btn-toolbar:after,.btn-toolbar:before,.clearfix:after,.clearfix:before,.container-fluid:after,.container-fluid:before,.container:after,.container:before,.dl-horizontal dd:after,.dl-horizontal dd:before,.form-horizontal .form-group:after,.form-horizontal .form-group:before,.modal-footer:after,.modal-footer:before,.modal-header:after,.modal-header:before,.nav:after,.nav:before,.navbar-collapse:after,.navbar-collapse:before,.navbar-header:after,.navbar-header:before,.navbar:after,.navbar:before,.pager:after,.pager:before,.panel-body:after,.panel-body:before,.row:after,.row:before{display:table;content:" "}.btn-group-vertical>.btn-group:after,.btn-toolbar:after,.clearfix:after,.container-fluid:after,.container:after,.dl-horizontal dd:after,.form-horizontal .form-group:after,.modal-footer:after,.modal-header:after,.nav:after,.navbar-collapse:after,.navbar-header:after,.navbar:after,.pager:after,.panel-body:after,.row:after{clear:both}.center-block{display:block;margin-right:auto;margin-left:auto}.pull-right{float:right!important}.pull-left{float:left!important}.hide{display:none!important}.show{display:block!important}.invisible{visibility:hidden}.text-hide{font:0/0 a;color:transparent;text-shadow:none;background-color:transparent;border:0}.hidden{display:none!important}.affix{position:fixed}@-ms-viewport{width:device-width}.visible-lg,.visible-md,.visible-sm,.visible-xs{display:none!important}.visible-lg-block,.visible-lg-inline,.visible-lg-inline-block,.visible-md-block,.visible-md-inline,.visible-md-inline-block,.visible-sm-block,.visible-sm-inline,.visible-sm-inline-block,.visible-xs-block,.visible-xs-inline,.visible-xs-inline-block{display:none!important}@media (max-width:767px){.visible-xs{display:block!important}table.visible-xs{display:table!important}tr.visible-xs{display:table-row!important}td.visible-xs,th.visible-xs{display:table-cell!important}}@media (max-width:767px){.visible-xs-block{display:block!important}}@media (max-width:767px){.visible-xs-inline{display:inline!important}}@media (max-width:767px){.visible-xs-inline-block{display:inline-block!important}}@media (min-width:768px) and (max-width:991px){.visible-sm{display:block!important}table.visible-sm{display:table!important}tr.visible-sm{display:table-row!important}td.visible-sm,th.visible-sm{display:table-cell!important}}@media (min-width:768px) and (max-width:991px){.visible-sm-block{display:block!important}}@media (min-width:768px) and (max-width:991px){.visible-sm-inline{display:inline!important}}@media (min-width:768px) and (max-width:991px){.visible-sm-inline-block{display:inline-block!important}}@media (min-width:992px) and (max-width:1199px){.visible-md{display:block!important}table.visible-md{display:table!important}tr.visible-md{display:table-row!important}td.visible-md,th.visible-md{display:table-cell!important}}@media (min-width:992px) and (max-width:1199px){.visible-md-block{display:block!important}}@media (min-width:992px) and (max-width:1199px){.visible-md-inline{display:inline!important}}@media (min-width:992px) and (max-width:1199px){.visible-md-inline-block{display:inline-block!important}}@media (min-width:1200px){.visible-lg{display:block!important}table.visible-lg{display:table!important}tr.visible-lg{display:table-row!important}td.visible-lg,th.visible-lg{display:table-cell!important}}@media (min-width:1200px){.visible-lg-block{display:block!important}}@media (min-width:1200px){.visible-lg-inline{display:inline!important}}@media (min-width:1200px){.visible-lg-inline-block{display:inline-block!important}}@media (max-width:767px){.hidden-xs{display:none!important}}@media (min-width:768px) and (max-width:991px){.hidden-sm{display:none!important}}@media (min-width:992px) and (max-width:1199px){.hidden-md{display:none!important}}@media (min-width:1200px){.hidden-lg{display:none!important}}.visible-print{display:none!important}@media print{.visible-print{display:block!important}table.visible-print{display:table!important}tr.visible-print{display:table-row!important}td.visible-print,th.visible-print{display:table-cell!important}}.visible-print-block{display:none!important}@media print{.visible-print-block{display:block!important}}.visible-print-inline{display:none!important}@media print{.visible-print-inline{display:inline!important}}.visible-print-inline-block{display:none!important}@media print{.visible-print-inline-block{display:inline-block!important}}@media print{.hidden-print{display:none!important}} +/*# sourceMappingURL=bootstrap.min.css.map */ diff --git a/mobile_manipulator/ifarlab_web/css/home.css b/mobile_manipulator/ifarlab_web/css/home.css new file mode 100644 index 0000000..965babb --- /dev/null +++ b/mobile_manipulator/ifarlab_web/css/home.css @@ -0,0 +1,481 @@ +.home-container { + width: auto; + /* display: flex; */ + overflow: auto; + min-height: 100vh; + transition: 0.3s; + align-items: center; + flex-direction: row; + justify-content: flex-start; +} + +.home-logo-value3s { + height: 80px; + width: auto; + display: block; + margin-left: auto; + margin-right: auto; +} + +.home-logo-ifarlab { + height: 80px; + width: auto; + display: block; + margin-left: auto; + margin-right: auto; +} + +.home-text { + margin-left: var(--dl-space-space-twounits); + text-decoration: none; +} +.home-text03 { + margin-left: var(--dl-space-space-twounits); +} +.home-text04 { + margin-left: var(--dl-space-space-twounits); +} +.home-text05 { + margin-left: var(--dl-space-space-twounits); +} +.home-btn-group { + display: flex; + align-items: center; + flex-direction: row; + justify-content: space-between; +} +.home-burger-menu { + display: none; + align-items: center; + justify-content: center; +} +.home-icon { + width: var(--dl-size-size-xsmall); + height: var(--dl-size-size-xsmall); +} +.home-mobile-menu { + top: 0px; + left: 0px; + width: 100%; + height: 100vh; + display: flex; + padding: 32px; + z-index: 100; + position: fixed; + transform: translateY(-100%); + transition: 0.5s; + flex-direction: column; + justify-content: space-between; + background-color: #fff; +} +.home-nav1 { + display: flex; + align-items: flex-start; + flex-direction: column; +} +.home-container01 { + width: 100%; + display: flex; + align-items: center; + margin-bottom: var(--dl-space-space-threeunits); + justify-content: space-between; +} +.home-image { + height: 2rem; +} +.home-menu-close { + display: flex; + align-items: center; + justify-content: center; +} +.home-icon02 { + width: var(--dl-size-size-xsmall); + height: var(--dl-size-size-xsmall); +} +.home-nav2 { + flex: 0 0 auto; + display: flex; + align-items: flex-start; + flex-direction: column; +} +.home-text06 { + margin-bottom: var(--dl-space-space-unit); +} +.home-text07 { + margin-bottom: var(--dl-space-space-unit); +} +.home-text08 { + margin-bottom: var(--dl-space-space-unit); +} +.home-text09 { + margin-bottom: var(--dl-space-space-unit); +} +.home-text10 { + margin-bottom: var(--dl-space-space-unit); +} +.home-container02 { + flex: 0 0 auto; + width: auto; + display: flex; + margin-top: var(--dl-space-space-unit); + align-items: center; + flex-direction: row; +} +.home-icon04 { + width: var(--dl-size-size-xsmall); + height: var(--dl-size-size-xsmall); + margin-right: var(--dl-space-space-twounits); +} +.home-icon06 { + width: var(--dl-size-size-xsmall); + height: var(--dl-size-size-xsmall); + margin-right: var(--dl-space-space-twounits); +} +.home-icon08 { + width: var(--dl-size-size-xsmall); + height: var(--dl-size-size-xsmall); +} +.home-container03 { + width: auto; + height: auto; + /* padding: 32px; */ + /* margin-left: -15px; */ + /*display: flex;*/ + /* padding: var(--dl-space-space-twounits); */ + /* position: relative; */ + /* align-items: flex-start; */ + /* flex-direction: row; */ + /* justify-content: flex-start; */ + /* border-color: #44b567; + border-style: groove; + border-width: 4px; */ +} +.home-text11 { + padding: 8px; + color: #204724; + font-size: 175%; + font-weight: bold; + text-align: center; + +} + +.apply-button{ + align-self: center; + box-shadow: 0px 2px 6px 0px #2b2626; + transition: 0.3s; + padding:12px 24px; + border-radius: 16px; + margin-top:16px; +} +.apply-button:active { + box-shadow: 0px 0px 0px 0px #2b2626; + background-color: #34ff2b; +} +/* Bootstrap borders*/ +.container{ + margin-top: 5%; +} + .col-border{ + padding: var(--dl-space-space-twounits); + border-color: #44b567; + border-style: groove; + border-width: 4px; + } + +.row-bottom-border{ + border-color: #44b567; + border-style: groove; + border-bottom: 4px; +} +.col-right-border{ + padding-left: 48px; + border-left:4px; + border-style: groove; + border-color: #44b567; +} +/* .col-sm-4{ + border-color: #44b567; + border-style: groove; + border-width: 4px; } */ +.config-text{ + text-size-adjust: auto; + text-align: center; + vertical-align:text-bottom; +} + + +/*-----*/ + +.home-container04 { + flex: 0 0 auto; + width: 100%; + height: auto; + display: flex; + align-items: center; + justify-content: flex-start; +} +.home-ul { + padding-left: 0; +} +.home-li { + list-style-type: none; + list-style-image: none; + list-style-position: outside; +} +.home-container05 { + flex: 0 0 auto; + width: auto; + height: auto; + display: flex; + padding: var(--dl-space-space-halfunit); + align-items: flex-start; + justify-content: flex-start; +} +.home-text16 { + align-self: center; + padding-right: 27px; +} +.home-textinput { + align-self: center; +} +.home-container06 { + flex: 0 0 auto; + width: auto; + height: auto; + display: flex; + padding: var(--dl-space-space-halfunit); + align-items: flex-start; + justify-content: flex-start; +} +.home-text17 { + align-self: center; + padding-right: 4px; + color: rgb(65, 147, 74); + text-size-adjust: 5%; + font-size: 16px; + font-weight: bold; +} +.home-textinput1 { + align-self: center; +} +.home-button { + width: 100%; + height: auto; + margin-left: 0px; + margin-right: 0px; + margin-top: var(--dl-space-space-unit); + margin-bottom: var(--dl-space-space-unit); + padding: var(--dl-space-space-twounits); + + transition: 0.3s; + + color: rgb(65, 147, 74); + font-size: 24px; + font-style: normal; + text-align: center; + font-weight: 700; + + border-color: #385623; + border-width: 1px; + border-radius: var(--dl-radius-radius-radius8); + background-color: rgb(237, 237, 237); + box-shadow: rgb(43, 38, 38) 0px 2px 10px 0px; + +} +.home-button:active { + color: #ffffff; + width: 100%; + align-self: center; + box-shadow: 0px 0px 0px 0px rgb(43, 38, 38); + background-color: #1fe53f; + cursor: pointer; +} +.home-button:hover { + color: #ffffff; + width: 100%; + align-self: center; + background-color: #1fe53f; + cursor: pointer; +} +.home-button1 { + width: 100%; + height: auto; + margin-left: 0px; + margin-right: 0px; + margin-top: var(--dl-space-space-unit); + margin-bottom: var(--dl-space-space-unit); + padding: var(--dl-space-space-twounits); + + transition: 0.3s; + + font-size: 24px; + color: rgb(65, 147, 74); + font-size: 24px; + font-style: normal; + text-align: center; + font-weight: 700; + + border-color: #385623; + border-width: 1px; + border-radius: var(--dl-radius-radius-radius8); + background-color: rgb(237, 237, 237); + box-shadow: 0px 2px 10px 0px #2b2626; +} +.home-button1:active { + color: #ffffff; + box-shadow: 0px 0px 0px 0px #2b2626; + border-color: rgba(0, 0, 0, 0.36); + background-color: #ff0000; +} +.home-button1:hover { + color: #ffffff; + border-color: rgba(0, 0, 0, 0.36); + background-color: #ff0000; + cursor: pointer; +} +.text-header{ + margin-top: 8px; + display: block; + position: inherit; + color: #ffffff; + font-size: 38px; + font-weight: bold; +} +.bottom-border{ + border-bottom: 4px; + border-style: groove; + border-color: #44b567; +} +.home-text18 { + font-size: 24px; + text-align: center; + padding-left: 0px; +} +.home-container07 { + flex: 0 0 auto; + width: 100%; + height: 100px; + display: flex; + align-items: center; + flex-direction: column; + justify-content: center; +} +.home-container08 { + flex: 0 0 auto; + width: auto; + height: auto; + display: flex; + align-items: flex-start; + justify-content: center; +} +.home-container09 { + flex: 0 0 auto; + width: auto; + height: auto; + display: flex; + align-items: flex-start; + justify-content: center; +} + +.config-label{ + padding: 2px; + font-weight: 700; + font-size: 18px; + color: rgb(65, 147, 74)}; + +.mr-echo{ + width: 100px; +} + +.icon-image{ + width: 100%; +} + +@media(max-width: 420px) { + .col-right-border { + margin-top: 15px; + padding-left: 0; + border-top:4px; + border-left: 0px; + border-style: groove; + border-color: #44b567; + } + .home-button1 { + font-size: 12px; + padding: 25px 0px; + } + .home-button { + font-size: 12px; + padding: 25px 0px; + } + .text-header{ + font-size: 24px; + } + .mr-echo{ + width: 80px; + } +} + +@media(max-width: 1200px) { + .home-logo-value3s { + height: 80px; + width: auto; + display: block; + margin-left: auto; + margin-right: auto; + margin-top: 12%; + } + .home-logo-ifarlab { + height: 80px; + width: auto; + display: block; + margin-left: auto; + margin-top: 12%; + } +} +/* +@media(max-width: 991px) { + .home-container { + animation-name: initial; + } +} +@media(max-width: 767px) { + .home-navbar-interactive { + flex: 0; + padding-left: var(--dl-space-space-twounits); + padding-right: var(--dl-space-space-twounits); + } + .home-text { + margin-left: var(--dl-space-space-unit); + } + .home-text01 { + margin-left: var(--dl-space-space-unit); + } + .home-text03 { + margin-left: var(--dl-space-space-unit); + } + .home-text04 { + margin-left: var(--dl-space-space-unit); + } + .home-text05 { + margin-left: var(--dl-space-space-unit); + } +} +@media(max-width: 479px) { + .home-navbar-interactive { + padding: var(--dl-space-space-unit); + } + .home-desktop-menu { + display: none; + } + .home-btn-group { + display: none; + } + .home-burger-menu { + display: flex; + } + .home-mobile-menu { + padding: 16px; + } +} +*/ \ No newline at end of file diff --git a/mobile_manipulator/ifarlab_web/css/home1.css b/mobile_manipulator/ifarlab_web/css/home1.css new file mode 100644 index 0000000..753f53e --- /dev/null +++ b/mobile_manipulator/ifarlab_web/css/home1.css @@ -0,0 +1,671 @@ +.home1-container { + width: 100%; + display: flex; + overflow: auto; + min-height: 100vh; + transition: 0.3s; + align-items: center; + border-color: #44b567; + border-style: groove; + border-width: 1px; + flex-direction: row; + justify-content: flex-start; +} + +.home1-container01 { + width: 100%; + display: flex; + align-items: center; + margin-bottom: var(--dl-space-space-threeunits); + justify-content: space-between; + border-color: #44b567; + border-style: groove; + border-width: 1px; +} + +.home1-container02 { + width: auto; + padding: 16px; + display: flex; + flex: 0 0 auto; + flex-direction: row; + margin-top: var(--dl-space-space-unit); + align-items: center; + position: relative; + /* border-color: #44b567; + border-style: groove; + border-width: 4px; */ +} + +.home1-container03 { + top: 85px; + flex: 0 0 auto; + left: -4px; + width: auto; + height: 258px; + display: flex; + position: absolute; + align-items: center; + justify-content: flex-start; + border-color: #44b567; + border-style: groove; + border-width: 1px; +} +.home1-container04 { + flex: 0 0 auto; + width: auto; + height: auto; + display: flex; + align-self: flex-start; + align-items: flex-start; + padding-top: var(--dl-space-space-oneandhalfunits); + padding-left: var(--dl-space-space-oneandhalfunits); + padding-right: var(--dl-space-space-oneandhalfunits); + flex-direction: column; + padding-bottom: var(--dl-space-space-oneandhalfunits); + justify-content: flex-start; + border-color: #44b567; + border-style: groove; + border-width: 1px; +} +.home1-text09 { + padding-top: var(--dl-space-space-halfunit); + padding-left: var(--dl-space-space-halfunit); + padding-right: var(--dl-space-space-halfunit); + padding-bottom: var(--dl-space-space-unit); +} +.home1-container05 { + flex: 0 0 auto; + width: auto; + height: auto; + display: flex; + align-items: flex-start; + flex-direction: column; + justify-content: center; + border-color: #44b567; + border-style: groove; + border-width: 1px; +} +.home1-container06 { + flex: 0 0 auto; + width: auto; + height: auto; + display: flex; + align-self: flex-start; + align-items: flex-start; + padding-top: var(--dl-space-space-oneandhalfunits); + padding-left: var(--dl-space-space-oneandhalfunits); + padding-right: var(--dl-space-space-oneandhalfunits); + flex-direction: column; + padding-bottom: var(--dl-space-space-oneandhalfunits); + justify-content: flex-start; + border-color: #221a97; + border-style: groove; + border-width: 4px; +} +.home1-text14 { + padding-top: var(--dl-space-space-halfunit); + padding-left: var(--dl-space-space-halfunit); + padding-right: var(--dl-space-space-halfunit); + padding-bottom: var(--dl-space-space-unit); + color: #204724; + font-size: 200%; + font-weight: bold; + text-align: center; +} +.home1-container07 { + flex: 0 0 auto; + width: 100%; + height: auto; + display: flex; + align-items: center; + padding-top: 0px; + padding: 1%; + flex-direction: row; + justify-content: flex-start; + border-color: #44b567; + border-style: groove; + border-width: 1px; +} +.home1-text15 { + padding-right: 56px; +} +.home1-textinput { + width: 100%; + height: 100%; +} +.home1-container08 { + flex: 0 0 auto; + width: 100%; + height: auto; + display: flex; + align-items: center; + padding-top: 8px; + flex-direction: row; + justify-content: flex-start; + border-color: #44b567; + border-style: groove; + border-width: 1px; +} +.home1-text16 { + padding-right: 30px; +} +.home1-textinput1 { + width: 100%; + height: 100%; +} +.home1-container09 { + flex: 0 0 auto; + width: 100%; + height: auto; + display: flex; + margin-top: 8px; + align-items: center; + flex-direction: row; + justify-content: flex-start; +} +.home1-text19 { + padding-right: 14px; +} +.home1-textinput2 { + width: 100%; + height: 100%; + padding-left: 1rem; +} +.home1-container10 { + flex: 0 0 auto; + width: auto; + height: auto; + display: flex; + align-items: center; + flex-direction: column; + border-color: #44b567; + border-style: groove; + border-width: 1px; +} +.home1-text20 { + padding: var(--dl-space-space-halfunit); +} +.home1-container11 { + flex: 0 0 auto; + width: 100%; + height: auto; + display: flex; + align-items: flex-start; + justify-content: flex-start; +} +.home1-container12 { + flex: 0 0 auto; + width: auto; + height: auto; + display: flex; + align-items: flex-start; + flex-direction: column; + justify-content: center; +} +.home1-text21 { + align-self: center; + text-align: center; + color: rgb(65, 147, 74); + font-weight: bold; +} +.home1-select { + cursor: pointer; + padding: var(--dl-space-space-halfunit); + z-index: 100; + align-self: center; + transition: 0.3s; + border-color: #bdbdbd; + border-width: 1px; + border-radius: var(--dl-radius-radius-radius4); +} + +.home1-select:active { + box-shadow: 0px 5px 10px 0px #d4d4d4; + cursor: pointer; +} +.home1-select:hover { + box-shadow: 0px 5px 10px 0px #d4d4d4; +} +.home1-textinput3 { + width: var(--dl-size-size-medium); + height: auto; + align-self: center; + transition: 0.3s; + display: none; +} +/*.home1-textinput3:active { + display: none; +} +.home1-textinput3:disabled { + display: none; +}*/ +.home1-button { + align-self: center; + box-shadow: 0px 2px 10px 0px #2b2626; + transition: 0.3s; +} +.home1-button:active { + box-shadow: 0px 0px 0px 0px #2b2626; + background-color: #34ff2b; +} +.home1-container13 { + flex: 0 0 auto; + width: auto; + height: auto; + display: flex; + align-items: flex-start; + flex-direction: column; + border-color: #44b567; + border-style: groove; + border-width: 1px; +} +.home1-container14 { + flex: 0 0 auto; + width: 200px; + height: auto; + display: flex; + align-items: center; + flex-direction: column; +} +.home1-text22 { + padding-bottom: var(--dl-space-space-halfunit); + text-align: center; + display: inline-block; +} + +.home1-container15 { + flex: 0 0 auto; + width: auto; + height: auto; + display: flex; + align-items: center; + justify-content: flex-start; +} +.home1-container16 { + flex: 0 0 auto; + width: auto; + height: auto; + display: flex; + align-items: flex-start; + flex-direction: row; + justify-content: flex-start; +} +.home1-container17 { + flex: 0 0 auto; + width: auto; + height: auto; + display: flex; + padding: var(--dl-space-space-unit); + align-items: flex-start; + padding-top: 16px; + flex-direction: column; + justify-content: center; +} +.home1-button1 { + width: 48px; + height: auto; + display: flex; + padding: var(--dl-space-space-halfunit); + align-self: center; + box-shadow: 0px 2px 10px 0px #2b2626; + transition: 0.3s; + align-items: center; + border-radius: var(--dl-radius-radius-round); + justify-content: center; +} +.home1-button1:active { + box-shadow: 0px 0px 0px 0px #2b2626; +} +.home1-icon10 { + width: auto; + align-self: stretch; +} +.home1-button2 { + width: 48px; + display: flex; + padding: var(--dl-space-space-halfunit); + box-shadow: 0px 2px 10px 0px #2b2626; + transition: 0.3s; + flex-direction: row; + background-color: #ff0000; +} +.home1-button2:active { + box-shadow: 0px 0px 0px 0px #2b2626; +} + +.home1-button4 { + width: 48px; + display: flex; + padding: var(--dl-space-space-halfunit); + box-shadow: 0px 2px 10px 0px #2b2626; + transition: 0.3s; + flex-direction: row; + background-color: #15ff00; +} +.home1-button4:active { + box-shadow: 0px 0px 0px 0px #2b2626; +} + +.home1-icon12 { + width: 100%; + height: 24px; +} +.home1-button3 { + width: 48px; + height: auto; + display: flex; + padding: 0px; + align-self: center; + box-shadow: 0px 2px 10px 0px #2b2626; + transition: 0.3s; + align-items: flex-end; + border-radius: var(--dl-radius-radius-round); + flex-direction: row; + justify-content: center; + border-top-left-radius: var(--dl-radius-radius-round); + border-top-right-radius: var(--dl-radius-radius-round); + border-bottom-left-radius: var(--dl-radius-radius-round); + border-bottom-right-radius: var(--dl-radius-radius-round); +} +.home1-button3:active { + box-shadow: 0px 0px 0px 0px #2b2626; +} +.home1-icon14 { + width: auto; + height: 100%; + padding: var(--dl-space-space-halfunit); + align-self: stretch; + transition: 0.3s; + border-radius: var(--dl-radius-radius-radius4); +} + +.home1-container18 { + flex: 0 0 auto; + width: auto; + height: auto; + display: flex; + align-items: flex-start; + flex-direction: column; +} +.home1-container19 { + flex: 0 0 auto; + width: auto; + height: auto; + display: flex; + align-items: flex-start; + flex-direction: column; +} +.home1-text23 { + padding: var(--dl-space-space-halfunit); +} +.home1-text24 { + padding: var(--dl-space-space-halfunit); +} +.home1-text25 { + padding: var(--dl-space-space-halfunit); +} +.home1-container20 { + flex: 0 0 auto; + width: auto; + height: auto; + display: flex; + align-items: flex-start; + flex-direction: column; +} +.home1-container21 { + flex: 0 0 auto; + width: auto; + height: auto; + display: flex; + align-items: flex-start; + flex-direction: column; +} + +/* The Modal (background) */ +.modal { + display: none; /* Hidden by default */ + position: fixed; /* Stay in place */ + z-index: 1; /* Sit on top */ + padding-top: 200px; /* Location of the box */ + left: 0; + top: 0; + width: 100%; /* Full width */ + height: 100%; /* Full height */ + overflow: auto; /* Enable scroll if needed */ + background-color: rgb(0,0,0); /* Fallback color */ + background-color: rgba(0,0,0,0.4); /* Black w/ opacity */ +} + +.modal-header { + padding: 16px 16px; + background-color: #a10707; + color: white; + text-align: center; + border-radius: 25px 25px 0px 0px; + font-size: 32px; +} + +.modal-body { + padding: 16px 16px; + +} + +.modal-button{ + border: 1px solid #888; + display: block; + margin-left: auto; + margin-right: auto; + box-shadow: 0px 2px 10px 0px #2b2626; + transition: 0.3s; + padding: 16px 16px; + +} +.modal-button:active { + box-shadow: 0px 0px 0px 0px #2b2626; + background-color: #34ff2b; +} + +.modal-footer { + padding: 16px; + border-top: 1px solid #888; +} +.emg-p { + padding: 8px; + font-size: 24px; +} +.modal-title{ + font-size: 38px; + font-weight: 700; +} +/* Modal Content */ +.modal-content { + position: relative; + background-color: #fefefe; + margin: auto; + padding: 0; + border: 1px solid #888; + border-radius: 25px; + width: 30%; + box-shadow: 0 4px 8px 0 rgba(0,0,0,0.2),0 6px 20px 0 rgba(0,0,0,0.19); + -webkit-animation-name: animatetop; + -webkit-animation-duration: 0.4s; + animation-name: animatetop; + animation-duration: 0.4s; + text-align: center; +} + +/* Add Animation */ +@-webkit-keyframes animatetop { + from {top:-300px; opacity:0} + to {top:0; opacity:1} +} + +@keyframes animatetop { + from {top:-300px; opacity:0} + to {top:0; opacity:1} +} + +/* The Close Button */ +.close { + color: black; + float: right; + font-size: 28px; + font-weight: bold; + cursor: pointer; + +} + +.robot_echo_data{ + padding: 16x; + color: #2b2626; + font-size: 16px; + width: 100%; +} + +/* @media(max-width: 991px) { + .home1-container { + animation-name: initial; + } + .home1-container03 { + height: auto; + } + .home1-container10 { + width: auto; + } + .home1-container12 { + align-items: flex-start; + flex-direction: column; + justify-content: center; + } + .home1-select { + margin: 1px; + align-self: center; + } + .home1-textinput3 { + width: var(--dl-size-size-medium); + height: auto; + margin: var(--dl-space-space-halfunit); + padding: 1px; + align-self: center; + } + .home1-button { + height: auto; + align-self: center; + } +} */ +/* @media(max-width: 767px) { + .home1-text { + margin-left: var(--dl-space-space-unit); + } + .home1-text01 { + margin-left: var(--dl-space-space-unit); + } + .home1-text02 { + margin-left: var(--dl-space-space-unit); + } + .home1-text03 { + margin-left: var(--dl-space-space-unit); + } +} +@media(max-width: 479px) { + .home1-desktop-menu { + display: none; + } + .home1-btn-group { + display: none; + } + .home1-burger-menu { + display: flex; + } + .home1-mobile-menu { + padding: 16px; + } + .home1-container03 { + width: auto; + } + .home1-container06 { + width: 100%; + } +} */ + +.switch { + position: relative; + display: inline-block; + width: 60px; + height: 34px; +} + +.switch input { + opacity: 0; + width: 0; + height: 0; +} + +.slider { + position: absolute; + cursor: pointer; + top: 0; + left: 0; + right: 0; + bottom: 0; + background-color: #ccc; + -webkit-transition: .4s; + transition: .4s; +} + +.slider:before { + position: absolute; + content: ""; + height: 26px; + width: 26px; + left: 4px; + bottom: 4px; + background-color: white; + -webkit-transition: .4s; + transition: .4s; +} + +input:checked + .slider { + background-color: #2196F3; +} + +input:focus + .slider { + box-shadow: 0 0 1px #2196F3; +} + +input:checked + .slider:before { + -webkit-transform: translateX(26px); + -ms-transform: translateX(26px); + transform: translateX(26px); +} + +/* Rounded sliders */ +.slider.round { + border-radius: 34px; +} + +.slider.round:before { + border-radius: 50%; +} + +@media(max-width: 1200px) { + .emg-p{ + padding: 4px; + text-align: center; + font-size: 18px; + } + .modal-title{ + font-size: 30px; + font-weight: 700; +} +} + +@media(max-width: 420px) { + .modal-content { + width: 70%; + } + .modal-title{ + font-size: 24px; + } +} diff --git a/mobile_manipulator/ifarlab_web/css/style.css b/mobile_manipulator/ifarlab_web/css/style.css new file mode 100644 index 0000000..38a3b09 --- /dev/null +++ b/mobile_manipulator/ifarlab_web/css/style.css @@ -0,0 +1,134 @@ +:root { + --dl-color-gray-500: #595959; + --dl-color-gray-700: #999999; + --dl-color-gray-900: #D9D9D9; + --dl-size-size-large: 144px; + --dl-size-size-small: 48px; + --dl-color-danger-300: #A22020; + --dl-color-danger-500: #BF2626; + --dl-color-danger-700: #E14747; + --dl-color-gray-black: #000000; + --dl-color-gray-white: #FFFFFF; + --dl-size-size-medium: 96px; + --dl-size-size-xlarge: 192px; + --dl-size-size-xsmall: 16px; + --dl-space-space-unit: 16px; + --dl-color-primary-100: #003EB3; + --dl-color-primary-300: #0074F0; + --dl-color-primary-500: #14A9FF; + --dl-color-primary-700: #85DCFF; + --dl-color-success-300: #199033; + --dl-color-success-500: #32A94C; + --dl-color-success-700: #4CC366; + --dl-size-size-xxlarge: 288px; + --dl-size-size-maxwidth: 1400px; + --dl-radius-radius-round: 50%; + --dl-space-space-halfunit: 8px; + --dl-space-space-sixunits: 96px; + --dl-space-space-twounits: 32px; + --dl-radius-radius-radius2: 2px; + --dl-radius-radius-radius4: 4px; + --dl-radius-radius-radius8: 8px; + --dl-space-space-fiveunits: 80px; + --dl-space-space-fourunits: 64px; + --dl-space-space-threeunits: 48px; + --dl-space-space-oneandhalfunits: 24px; +} +.button { + color: var(--dl-color-gray-black); + cursor: pointer; + display: inline-block; + padding: 0.5rem 1rem; + border-color: var(--dl-color-gray-black); + border-width: 1px; + border-radius: 4px; + background-color: var(--dl-color-gray-white); +} + + +.input { + color: var(--dl-color-gray-black); + cursor: auto; + padding: 0.5rem 1rem; + border-color: var(--dl-color-gray-black); + border-width: 1px; + border-radius: 4px; + background-color: var(--dl-color-gray-white); + width: 100%; +} +.textarea { + color: var(--dl-color-gray-black); + cursor: auto; + padding: 0.5rem; + border-color: var(--dl-color-gray-black); + border-width: 1px; + border-radius: 4px; + background-color: var(--dl-color-gray-white); +} +.list { + width: 100%; + margin: 1em 0px 1em 0px; + display: block; + padding: 0px 0px 0px 1.5rem; + list-style-type: none; + list-style-position: outside; +} +.list-item { + display: list-item; +} +.teleport-show { + display: flex !important; + transform: translateY(0%) !important; +} +.baslat { + color: var(--dl-color-primary-500); + transition: 0.3s; + font-family: Arial; + background-color: var(--dl-color-success-300); +} +.baslat:active { + color: #0b9bea; + z-index: 100; + align-self: center; + box-shadow: 5px 5px 10px 0px rgba(212, 212, 212, 0.86); + background-color: var(--dl-color-gray-black); +} +.navarea { + top: 1px; + left: 0px; + /* width: 100%; */ + display: block; + position: inherit; + align-self: flex-start; + flex-direction: cloumn; + background-color: #418f49; +} +.Content { + font-size: 16px; + font-family: Inter; + font-weight: 400; + line-height: 1.15; + text-transform: none; + text-decoration: none; +} +.Heading { + font-size: 32px; + font-family: Inter; + font-weight: 700; + line-height: 1.15; + text-transform: none; + text-decoration: none; +} + +/* @media(max-width: 767px) { + .navarea { + flex: 0; + padding-left: var(--dl-space-space-twounits); + padding-right: var(--dl-space-space-twounits); + } +} +@media(max-width: 479px) { + .navarea { + padding: var(--dl-space-space-unit); + } +}*/ diff --git a/mobile_manipulator/ifarlab_web/img/ifarlab_logo.jpeg b/mobile_manipulator/ifarlab_web/img/ifarlab_logo.jpeg new file mode 100644 index 0000000..ffec031 Binary files /dev/null and b/mobile_manipulator/ifarlab_web/img/ifarlab_logo.jpeg differ diff --git a/mobile_manipulator/ifarlab_web/img/ifarlab_logo.png b/mobile_manipulator/ifarlab_web/img/ifarlab_logo.png new file mode 100644 index 0000000..c41f464 Binary files /dev/null and b/mobile_manipulator/ifarlab_web/img/ifarlab_logo.png differ diff --git a/mobile_manipulator/ifarlab_web/img/industrial-robot.png b/mobile_manipulator/ifarlab_web/img/industrial-robot.png new file mode 100644 index 0000000..7814e50 Binary files /dev/null and b/mobile_manipulator/ifarlab_web/img/industrial-robot.png differ diff --git a/mobile_manipulator/ifarlab_web/img/value3s.png b/mobile_manipulator/ifarlab_web/img/value3s.png new file mode 100644 index 0000000..7a8102c Binary files /dev/null and b/mobile_manipulator/ifarlab_web/img/value3s.png differ diff --git a/mobile_manipulator/ifarlab_web/index_v2.html b/mobile_manipulator/ifarlab_web/index_v2.html new file mode 100644 index 0000000..09faea1 --- /dev/null +++ b/mobile_manipulator/ifarlab_web/index_v2.html @@ -0,0 +1,322 @@ + + + + Rokos Chasis Inspection + + + + + + + + + + + + + + + + + +
+ + + +
+ +
+
+
+
Robot Configuration
+
+
+ +
+
+
+ +
+
+ +
+
+
+
+
+ +
+
+
+
+ Chassis Inspection +
+
+ +
+
+ Manuel Movement +
+
+
+
+
+
+
+
Task Tracking
+
+
+
+
+ Task Status : +
+
+ +
+
+
+
+ Task List : +
+
+
    +
    +
    +
    +
    + Active Task ID : +
    +
    + +
    +
    +
    +
    +
    +
    +
    +
    +
    Manuel Controlling
    +
    +
    +
    + +
    +
    + Manipulator Stop +
    +
    + +
    +
    + Manipulator Home +
    +
    + +
    +
    +
    +
    + Manuel Drive +
    +
    +
    + +
    +
    + +
    +
    + +
    +
    +
    +
    +
    + Robot Data +
    +
    +
    + Robot Position +
    +
    + +
    +
    + Robot Velocity +
    +
    + +
    +
    + Robot Status +
    +
    + +
    +
    +
    +
    +
    + +
    +
    +
    + +
    + +
    +
    + +
    + +
    + +
    + +
    + + +
    +
    + + +
    +
    +
    + + + + + + + + diff --git a/mobile_manipulator/ifarlab_web/js/bootstrap.min.js b/mobile_manipulator/ifarlab_web/js/bootstrap.min.js new file mode 100644 index 0000000..125a419 --- /dev/null +++ b/mobile_manipulator/ifarlab_web/js/bootstrap.min.js @@ -0,0 +1,7 @@ +/*! + * Bootstrap v4.6.2 (https://getbootstrap.com/) + * Copyright 2011-2022 The Bootstrap Authors (https://github.com/twbs/bootstrap/graphs/contributors) + * Licensed under MIT (https://github.com/twbs/bootstrap/blob/main/LICENSE) + */ +!function(t,e){"object"==typeof exports&&"undefined"!=typeof module?e(exports,require("jquery"),require("popper.js")):"function"==typeof define&&define.amd?define(["exports","jquery","popper.js"],e):e((t="undefined"!=typeof globalThis?globalThis:t||self).bootstrap={},t.jQuery,t.Popper)}(this,(function(t,e,n){"use strict";function i(t){return t&&"object"==typeof t&&"default"in t?t:{default:t}}var o=i(e),a=i(n);function s(t,e){for(var n=0;n=4)throw new Error("Bootstrap's JavaScript requires at least jQuery v1.9.1 but less than v4.0.0")}};d.jQueryDetection(),o.default.fn.emulateTransitionEnd=function(t){var e=this,n=!1;return o.default(this).one(d.TRANSITION_END,(function(){n=!0})),setTimeout((function(){n||d.triggerTransitionEnd(e)}),t),this},o.default.event.special[d.TRANSITION_END]={bindType:f,delegateType:f,handle:function(t){if(o.default(t.target).is(this))return t.handleObj.handler.apply(this,arguments)}};var c="bs.alert",h=o.default.fn.alert,g=function(){function t(t){this._element=t}var e=t.prototype;return e.close=function(t){var e=this._element;t&&(e=this._getRootElement(t)),this._triggerCloseEvent(e).isDefaultPrevented()||this._removeElement(e)},e.dispose=function(){o.default.removeData(this._element,c),this._element=null},e._getRootElement=function(t){var e=d.getSelectorFromElement(t),n=!1;return e&&(n=document.querySelector(e)),n||(n=o.default(t).closest(".alert")[0]),n},e._triggerCloseEvent=function(t){var e=o.default.Event("close.bs.alert");return o.default(t).trigger(e),e},e._removeElement=function(t){var e=this;if(o.default(t).removeClass("show"),o.default(t).hasClass("fade")){var n=d.getTransitionDurationFromElement(t);o.default(t).one(d.TRANSITION_END,(function(n){return e._destroyElement(t,n)})).emulateTransitionEnd(n)}else this._destroyElement(t)},e._destroyElement=function(t){o.default(t).detach().trigger("closed.bs.alert").remove()},t._jQueryInterface=function(e){return this.each((function(){var n=o.default(this),i=n.data(c);i||(i=new t(this),n.data(c,i)),"close"===e&&i[e](this)}))},t._handleDismiss=function(t){return function(e){e&&e.preventDefault(),t.close(this)}},l(t,null,[{key:"VERSION",get:function(){return"4.6.2"}}]),t}();o.default(document).on("click.bs.alert.data-api",'[data-dismiss="alert"]',g._handleDismiss(new g)),o.default.fn.alert=g._jQueryInterface,o.default.fn.alert.Constructor=g,o.default.fn.alert.noConflict=function(){return o.default.fn.alert=h,g._jQueryInterface};var m="bs.button",p=o.default.fn.button,_="active",v='[data-toggle^="button"]',y='input:not([type="hidden"])',b=".btn",E=function(){function t(t){this._element=t,this.shouldAvoidTriggerChange=!1}var e=t.prototype;return e.toggle=function(){var t=!0,e=!0,n=o.default(this._element).closest('[data-toggle="buttons"]')[0];if(n){var i=this._element.querySelector(y);if(i){if("radio"===i.type)if(i.checked&&this._element.classList.contains(_))t=!1;else{var a=n.querySelector(".active");a&&o.default(a).removeClass(_)}t&&("checkbox"!==i.type&&"radio"!==i.type||(i.checked=!this._element.classList.contains(_)),this.shouldAvoidTriggerChange||o.default(i).trigger("change")),i.focus(),e=!1}}this._element.hasAttribute("disabled")||this._element.classList.contains("disabled")||(e&&this._element.setAttribute("aria-pressed",!this._element.classList.contains(_)),t&&o.default(this._element).toggleClass(_))},e.dispose=function(){o.default.removeData(this._element,m),this._element=null},t._jQueryInterface=function(e,n){return this.each((function(){var i=o.default(this),a=i.data(m);a||(a=new t(this),i.data(m,a)),a.shouldAvoidTriggerChange=n,"toggle"===e&&a[e]()}))},l(t,null,[{key:"VERSION",get:function(){return"4.6.2"}}]),t}();o.default(document).on("click.bs.button.data-api",v,(function(t){var e=t.target,n=e;if(o.default(e).hasClass("btn")||(e=o.default(e).closest(b)[0]),!e||e.hasAttribute("disabled")||e.classList.contains("disabled"))t.preventDefault();else{var i=e.querySelector(y);if(i&&(i.hasAttribute("disabled")||i.classList.contains("disabled")))return void t.preventDefault();"INPUT"!==n.tagName&&"LABEL"===e.tagName||E._jQueryInterface.call(o.default(e),"toggle","INPUT"===n.tagName)}})).on("focus.bs.button.data-api blur.bs.button.data-api",v,(function(t){var e=o.default(t.target).closest(b)[0];o.default(e).toggleClass("focus",/^focus(in)?$/.test(t.type))})),o.default(window).on("load.bs.button.data-api",(function(){for(var t=[].slice.call(document.querySelectorAll('[data-toggle="buttons"] .btn')),e=0,n=t.length;e0,this._pointerEvent=Boolean(window.PointerEvent||window.MSPointerEvent),this._addEventListeners()}var e=t.prototype;return e.next=function(){this._isSliding||this._slide(N)},e.nextWhenVisible=function(){var t=o.default(this._element);!document.hidden&&t.is(":visible")&&"hidden"!==t.css("visibility")&&this.next()},e.prev=function(){this._isSliding||this._slide(D)},e.pause=function(t){t||(this._isPaused=!0),this._element.querySelector(".carousel-item-next, .carousel-item-prev")&&(d.triggerTransitionEnd(this._element),this.cycle(!0)),clearInterval(this._interval),this._interval=null},e.cycle=function(t){t||(this._isPaused=!1),this._interval&&(clearInterval(this._interval),this._interval=null),this._config.interval&&!this._isPaused&&(this._updateInterval(),this._interval=setInterval((document.visibilityState?this.nextWhenVisible:this.next).bind(this),this._config.interval))},e.to=function(t){var e=this;this._activeElement=this._element.querySelector(I);var n=this._getItemIndex(this._activeElement);if(!(t>this._items.length-1||t<0))if(this._isSliding)o.default(this._element).one(A,(function(){return e.to(t)}));else{if(n===t)return this.pause(),void this.cycle();var i=t>n?N:D;this._slide(i,this._items[t])}},e.dispose=function(){o.default(this._element).off(".bs.carousel"),o.default.removeData(this._element,w),this._items=null,this._config=null,this._element=null,this._interval=null,this._isPaused=null,this._isSliding=null,this._activeElement=null,this._indicatorsElement=null},e._getConfig=function(t){return t=r({},k,t),d.typeCheckConfig(T,t,O),t},e._handleSwipe=function(){var t=Math.abs(this.touchDeltaX);if(!(t<=40)){var e=t/this.touchDeltaX;this.touchDeltaX=0,e>0&&this.prev(),e<0&&this.next()}},e._addEventListeners=function(){var t=this;this._config.keyboard&&o.default(this._element).on("keydown.bs.carousel",(function(e){return t._keydown(e)})),"hover"===this._config.pause&&o.default(this._element).on("mouseenter.bs.carousel",(function(e){return t.pause(e)})).on("mouseleave.bs.carousel",(function(e){return t.cycle(e)})),this._config.touch&&this._addTouchEventListeners()},e._addTouchEventListeners=function(){var t=this;if(this._touchSupported){var e=function(e){t._pointerEvent&&j[e.originalEvent.pointerType.toUpperCase()]?t.touchStartX=e.originalEvent.clientX:t._pointerEvent||(t.touchStartX=e.originalEvent.touches[0].clientX)},n=function(e){t._pointerEvent&&j[e.originalEvent.pointerType.toUpperCase()]&&(t.touchDeltaX=e.originalEvent.clientX-t.touchStartX),t._handleSwipe(),"hover"===t._config.pause&&(t.pause(),t.touchTimeout&&clearTimeout(t.touchTimeout),t.touchTimeout=setTimeout((function(e){return t.cycle(e)}),500+t._config.interval))};o.default(this._element.querySelectorAll(".carousel-item img")).on("dragstart.bs.carousel",(function(t){return t.preventDefault()})),this._pointerEvent?(o.default(this._element).on("pointerdown.bs.carousel",(function(t){return e(t)})),o.default(this._element).on("pointerup.bs.carousel",(function(t){return n(t)})),this._element.classList.add("pointer-event")):(o.default(this._element).on("touchstart.bs.carousel",(function(t){return e(t)})),o.default(this._element).on("touchmove.bs.carousel",(function(e){return function(e){t.touchDeltaX=e.originalEvent.touches&&e.originalEvent.touches.length>1?0:e.originalEvent.touches[0].clientX-t.touchStartX}(e)})),o.default(this._element).on("touchend.bs.carousel",(function(t){return n(t)})))}},e._keydown=function(t){if(!/input|textarea/i.test(t.target.tagName))switch(t.which){case 37:t.preventDefault(),this.prev();break;case 39:t.preventDefault(),this.next()}},e._getItemIndex=function(t){return this._items=t&&t.parentNode?[].slice.call(t.parentNode.querySelectorAll(".carousel-item")):[],this._items.indexOf(t)},e._getItemByDirection=function(t,e){var n=t===N,i=t===D,o=this._getItemIndex(e),a=this._items.length-1;if((i&&0===o||n&&o===a)&&!this._config.wrap)return e;var s=(o+(t===D?-1:1))%this._items.length;return-1===s?this._items[this._items.length-1]:this._items[s]},e._triggerSlideEvent=function(t,e){var n=this._getItemIndex(t),i=this._getItemIndex(this._element.querySelector(I)),a=o.default.Event("slide.bs.carousel",{relatedTarget:t,direction:e,from:i,to:n});return o.default(this._element).trigger(a),a},e._setActiveIndicatorElement=function(t){if(this._indicatorsElement){var e=[].slice.call(this._indicatorsElement.querySelectorAll(".active"));o.default(e).removeClass(S);var n=this._indicatorsElement.children[this._getItemIndex(t)];n&&o.default(n).addClass(S)}},e._updateInterval=function(){var t=this._activeElement||this._element.querySelector(I);if(t){var e=parseInt(t.getAttribute("data-interval"),10);e?(this._config.defaultInterval=this._config.defaultInterval||this._config.interval,this._config.interval=e):this._config.interval=this._config.defaultInterval||this._config.interval}},e._slide=function(t,e){var n,i,a,s=this,l=this._element.querySelector(I),r=this._getItemIndex(l),u=e||l&&this._getItemByDirection(t,l),f=this._getItemIndex(u),c=Boolean(this._interval);if(t===N?(n="carousel-item-left",i="carousel-item-next",a="left"):(n="carousel-item-right",i="carousel-item-prev",a="right"),u&&o.default(u).hasClass(S))this._isSliding=!1;else if(!this._triggerSlideEvent(u,a).isDefaultPrevented()&&l&&u){this._isSliding=!0,c&&this.pause(),this._setActiveIndicatorElement(u),this._activeElement=u;var h=o.default.Event(A,{relatedTarget:u,direction:a,from:r,to:f});if(o.default(this._element).hasClass("slide")){o.default(u).addClass(i),d.reflow(u),o.default(l).addClass(n),o.default(u).addClass(n);var g=d.getTransitionDurationFromElement(l);o.default(l).one(d.TRANSITION_END,(function(){o.default(u).removeClass(n+" "+i).addClass(S),o.default(l).removeClass("active "+i+" "+n),s._isSliding=!1,setTimeout((function(){return o.default(s._element).trigger(h)}),0)})).emulateTransitionEnd(g)}else o.default(l).removeClass(S),o.default(u).addClass(S),this._isSliding=!1,o.default(this._element).trigger(h);c&&this.cycle()}},t._jQueryInterface=function(e){return this.each((function(){var n=o.default(this).data(w),i=r({},k,o.default(this).data());"object"==typeof e&&(i=r({},i,e));var a="string"==typeof e?e:i.slide;if(n||(n=new t(this,i),o.default(this).data(w,n)),"number"==typeof e)n.to(e);else if("string"==typeof a){if("undefined"==typeof n[a])throw new TypeError('No method named "'+a+'"');n[a]()}else i.interval&&i.ride&&(n.pause(),n.cycle())}))},t._dataApiClickHandler=function(e){var n=d.getSelectorFromElement(this);if(n){var i=o.default(n)[0];if(i&&o.default(i).hasClass("carousel")){var a=r({},o.default(i).data(),o.default(this).data()),s=this.getAttribute("data-slide-to");s&&(a.interval=!1),t._jQueryInterface.call(o.default(i),a),s&&o.default(i).data(w).to(s),e.preventDefault()}}},l(t,null,[{key:"VERSION",get:function(){return"4.6.2"}},{key:"Default",get:function(){return k}}]),t}();o.default(document).on("click.bs.carousel.data-api","[data-slide], [data-slide-to]",P._dataApiClickHandler),o.default(window).on("load.bs.carousel.data-api",(function(){for(var t=[].slice.call(document.querySelectorAll('[data-ride="carousel"]')),e=0,n=t.length;e0&&(this._selector=s,this._triggerArray.push(a))}this._parent=this._config.parent?this._getParent():null,this._config.parent||this._addAriaAndCollapsedClass(this._element,this._triggerArray),this._config.toggle&&this.toggle()}var e=t.prototype;return e.toggle=function(){o.default(this._element).hasClass(q)?this.hide():this.show()},e.show=function(){var e,n,i=this;if(!(this._isTransitioning||o.default(this._element).hasClass(q)||(this._parent&&0===(e=[].slice.call(this._parent.querySelectorAll(".show, .collapsing")).filter((function(t){return"string"==typeof i._config.parent?t.getAttribute("data-parent")===i._config.parent:t.classList.contains(F)}))).length&&(e=null),e&&(n=o.default(e).not(this._selector).data(R))&&n._isTransitioning))){var a=o.default.Event("show.bs.collapse");if(o.default(this._element).trigger(a),!a.isDefaultPrevented()){e&&(t._jQueryInterface.call(o.default(e).not(this._selector),"hide"),n||o.default(e).data(R,null));var s=this._getDimension();o.default(this._element).removeClass(F).addClass(Q),this._element.style[s]=0,this._triggerArray.length&&o.default(this._triggerArray).removeClass(B).attr("aria-expanded",!0),this.setTransitioning(!0);var l="scroll"+(s[0].toUpperCase()+s.slice(1)),r=d.getTransitionDurationFromElement(this._element);o.default(this._element).one(d.TRANSITION_END,(function(){o.default(i._element).removeClass(Q).addClass("collapse show"),i._element.style[s]="",i.setTransitioning(!1),o.default(i._element).trigger("shown.bs.collapse")})).emulateTransitionEnd(r),this._element.style[s]=this._element[l]+"px"}}},e.hide=function(){var t=this;if(!this._isTransitioning&&o.default(this._element).hasClass(q)){var e=o.default.Event("hide.bs.collapse");if(o.default(this._element).trigger(e),!e.isDefaultPrevented()){var n=this._getDimension();this._element.style[n]=this._element.getBoundingClientRect()[n]+"px",d.reflow(this._element),o.default(this._element).addClass(Q).removeClass("collapse show");var i=this._triggerArray.length;if(i>0)for(var a=0;a0},e._getOffset=function(){var t=this,e={};return"function"==typeof this._config.offset?e.fn=function(e){return e.offsets=r({},e.offsets,t._config.offset(e.offsets,t._element)),e}:e.offset=this._config.offset,e},e._getPopperConfig=function(){var t={placement:this._getPlacement(),modifiers:{offset:this._getOffset(),flip:{enabled:this._config.flip},preventOverflow:{boundariesElement:this._config.boundary}}};return"static"===this._config.display&&(t.modifiers.applyStyle={enabled:!1}),r({},t,this._config.popperConfig)},t._jQueryInterface=function(e){return this.each((function(){var n=o.default(this).data(K);if(n||(n=new t(this,"object"==typeof e?e:null),o.default(this).data(K,n)),"string"==typeof e){if("undefined"==typeof n[e])throw new TypeError('No method named "'+e+'"');n[e]()}}))},t._clearMenus=function(e){if(!e||3!==e.which&&("keyup"!==e.type||9===e.which))for(var n=[].slice.call(document.querySelectorAll(it)),i=0,a=n.length;i0&&s--,40===e.which&&sdocument.documentElement.clientHeight;n||(this._element.style.overflowY="hidden"),this._element.classList.add(ht);var i=d.getTransitionDurationFromElement(this._dialog);o.default(this._element).off(d.TRANSITION_END),o.default(this._element).one(d.TRANSITION_END,(function(){t._element.classList.remove(ht),n||o.default(t._element).one(d.TRANSITION_END,(function(){t._element.style.overflowY=""})).emulateTransitionEnd(t._element,i)})).emulateTransitionEnd(i),this._element.focus()}},e._showElement=function(t){var e=this,n=o.default(this._element).hasClass(dt),i=this._dialog?this._dialog.querySelector(".modal-body"):null;this._element.parentNode&&this._element.parentNode.nodeType===Node.ELEMENT_NODE||document.body.appendChild(this._element),this._element.style.display="block",this._element.removeAttribute("aria-hidden"),this._element.setAttribute("aria-modal",!0),this._element.setAttribute("role","dialog"),o.default(this._dialog).hasClass("modal-dialog-scrollable")&&i?i.scrollTop=0:this._element.scrollTop=0,n&&d.reflow(this._element),o.default(this._element).addClass(ct),this._config.focus&&this._enforceFocus();var a=o.default.Event("shown.bs.modal",{relatedTarget:t}),s=function(){e._config.focus&&e._element.focus(),e._isTransitioning=!1,o.default(e._element).trigger(a)};if(n){var l=d.getTransitionDurationFromElement(this._dialog);o.default(this._dialog).one(d.TRANSITION_END,s).emulateTransitionEnd(l)}else s()},e._enforceFocus=function(){var t=this;o.default(document).off(pt).on(pt,(function(e){document!==e.target&&t._element!==e.target&&0===o.default(t._element).has(e.target).length&&t._element.focus()}))},e._setEscapeEvent=function(){var t=this;this._isShown?o.default(this._element).on(yt,(function(e){t._config.keyboard&&27===e.which?(e.preventDefault(),t.hide()):t._config.keyboard||27!==e.which||t._triggerBackdropTransition()})):this._isShown||o.default(this._element).off(yt)},e._setResizeEvent=function(){var t=this;this._isShown?o.default(window).on(_t,(function(e){return t.handleUpdate(e)})):o.default(window).off(_t)},e._hideModal=function(){var t=this;this._element.style.display="none",this._element.setAttribute("aria-hidden",!0),this._element.removeAttribute("aria-modal"),this._element.removeAttribute("role"),this._isTransitioning=!1,this._showBackdrop((function(){o.default(document.body).removeClass(ft),t._resetAdjustments(),t._resetScrollbar(),o.default(t._element).trigger(gt)}))},e._removeBackdrop=function(){this._backdrop&&(o.default(this._backdrop).remove(),this._backdrop=null)},e._showBackdrop=function(t){var e=this,n=o.default(this._element).hasClass(dt)?dt:"";if(this._isShown&&this._config.backdrop){if(this._backdrop=document.createElement("div"),this._backdrop.className="modal-backdrop",n&&this._backdrop.classList.add(n),o.default(this._backdrop).appendTo(document.body),o.default(this._element).on(vt,(function(t){e._ignoreBackdropClick?e._ignoreBackdropClick=!1:t.target===t.currentTarget&&("static"===e._config.backdrop?e._triggerBackdropTransition():e.hide())})),n&&d.reflow(this._backdrop),o.default(this._backdrop).addClass(ct),!t)return;if(!n)return void t();var i=d.getTransitionDurationFromElement(this._backdrop);o.default(this._backdrop).one(d.TRANSITION_END,t).emulateTransitionEnd(i)}else if(!this._isShown&&this._backdrop){o.default(this._backdrop).removeClass(ct);var a=function(){e._removeBackdrop(),t&&t()};if(o.default(this._element).hasClass(dt)){var s=d.getTransitionDurationFromElement(this._backdrop);o.default(this._backdrop).one(d.TRANSITION_END,a).emulateTransitionEnd(s)}else a()}else t&&t()},e._adjustDialog=function(){var t=this._element.scrollHeight>document.documentElement.clientHeight;!this._isBodyOverflowing&&t&&(this._element.style.paddingLeft=this._scrollbarWidth+"px"),this._isBodyOverflowing&&!t&&(this._element.style.paddingRight=this._scrollbarWidth+"px")},e._resetAdjustments=function(){this._element.style.paddingLeft="",this._element.style.paddingRight=""},e._checkScrollbar=function(){var t=document.body.getBoundingClientRect();this._isBodyOverflowing=Math.round(t.left+t.right)
    ',trigger:"hover focus",title:"",delay:0,html:!1,selector:!1,placement:"top",offset:0,container:!1,fallbackPlacement:"flip",boundary:"scrollParent",customClass:"",sanitize:!0,sanitizeFn:null,whiteList:{"*":["class","dir","id","lang","role",/^aria-[\w-]*$/i],a:["target","href","title","rel"],area:[],b:[],br:[],col:[],code:[],div:[],em:[],hr:[],h1:[],h2:[],h3:[],h4:[],h5:[],h6:[],i:[],img:["src","srcset","alt","title","width","height"],li:[],ol:[],p:[],pre:[],s:[],small:[],span:[],sub:[],sup:[],strong:[],u:[],ul:[]},popperConfig:null},Ut={animation:"boolean",template:"string",title:"(string|element|function)",trigger:"string",delay:"(number|object)",html:"boolean",selector:"(string|boolean)",placement:"(string|function)",offset:"(number|string|function)",container:"(string|element|boolean)",fallbackPlacement:"(string|array)",boundary:"(string|element)",customClass:"(string|function)",sanitize:"boolean",sanitizeFn:"(null|function)",whiteList:"object",popperConfig:"(null|object)"},Mt={HIDE:"hide.bs.tooltip",HIDDEN:"hidden.bs.tooltip",SHOW:"show.bs.tooltip",SHOWN:"shown.bs.tooltip",INSERTED:"inserted.bs.tooltip",CLICK:"click.bs.tooltip",FOCUSIN:"focusin.bs.tooltip",FOCUSOUT:"focusout.bs.tooltip",MOUSEENTER:"mouseenter.bs.tooltip",MOUSELEAVE:"mouseleave.bs.tooltip"},Wt=function(){function t(t,e){if("undefined"==typeof a.default)throw new TypeError("Bootstrap's tooltips require Popper (https://popper.js.org)");this._isEnabled=!0,this._timeout=0,this._hoverState="",this._activeTrigger={},this._popper=null,this.element=t,this.config=this._getConfig(e),this.tip=null,this._setListeners()}var e=t.prototype;return e.enable=function(){this._isEnabled=!0},e.disable=function(){this._isEnabled=!1},e.toggleEnabled=function(){this._isEnabled=!this._isEnabled},e.toggle=function(t){if(this._isEnabled)if(t){var e=this.constructor.DATA_KEY,n=o.default(t.currentTarget).data(e);n||(n=new this.constructor(t.currentTarget,this._getDelegateConfig()),o.default(t.currentTarget).data(e,n)),n._activeTrigger.click=!n._activeTrigger.click,n._isWithActiveTrigger()?n._enter(null,n):n._leave(null,n)}else{if(o.default(this.getTipElement()).hasClass(Rt))return void this._leave(null,this);this._enter(null,this)}},e.dispose=function(){clearTimeout(this._timeout),o.default.removeData(this.element,this.constructor.DATA_KEY),o.default(this.element).off(this.constructor.EVENT_KEY),o.default(this.element).closest(".modal").off("hide.bs.modal",this._hideModalHandler),this.tip&&o.default(this.tip).remove(),this._isEnabled=null,this._timeout=null,this._hoverState=null,this._activeTrigger=null,this._popper&&this._popper.destroy(),this._popper=null,this.element=null,this.config=null,this.tip=null},e.show=function(){var t=this;if("none"===o.default(this.element).css("display"))throw new Error("Please use show on visible elements");var e=o.default.Event(this.constructor.Event.SHOW);if(this.isWithContent()&&this._isEnabled){o.default(this.element).trigger(e);var n=d.findShadowRoot(this.element),i=o.default.contains(null!==n?n:this.element.ownerDocument.documentElement,this.element);if(e.isDefaultPrevented()||!i)return;var s=this.getTipElement(),l=d.getUID(this.constructor.NAME);s.setAttribute("id",l),this.element.setAttribute("aria-describedby",l),this.setContent(),this.config.animation&&o.default(s).addClass(Lt);var r="function"==typeof this.config.placement?this.config.placement.call(this,s,this.element):this.config.placement,u=this._getAttachment(r);this.addAttachmentClass(u);var f=this._getContainer();o.default(s).data(this.constructor.DATA_KEY,this),o.default.contains(this.element.ownerDocument.documentElement,this.tip)||o.default(s).appendTo(f),o.default(this.element).trigger(this.constructor.Event.INSERTED),this._popper=new a.default(this.element,s,this._getPopperConfig(u)),o.default(s).addClass(Rt),o.default(s).addClass(this.config.customClass),"ontouchstart"in document.documentElement&&o.default(document.body).children().on("mouseover",null,o.default.noop);var c=function(){t.config.animation&&t._fixTransition();var e=t._hoverState;t._hoverState=null,o.default(t.element).trigger(t.constructor.Event.SHOWN),e===qt&&t._leave(null,t)};if(o.default(this.tip).hasClass(Lt)){var h=d.getTransitionDurationFromElement(this.tip);o.default(this.tip).one(d.TRANSITION_END,c).emulateTransitionEnd(h)}else c()}},e.hide=function(t){var e=this,n=this.getTipElement(),i=o.default.Event(this.constructor.Event.HIDE),a=function(){e._hoverState!==xt&&n.parentNode&&n.parentNode.removeChild(n),e._cleanTipClass(),e.element.removeAttribute("aria-describedby"),o.default(e.element).trigger(e.constructor.Event.HIDDEN),null!==e._popper&&e._popper.destroy(),t&&t()};if(o.default(this.element).trigger(i),!i.isDefaultPrevented()){if(o.default(n).removeClass(Rt),"ontouchstart"in document.documentElement&&o.default(document.body).children().off("mouseover",null,o.default.noop),this._activeTrigger.click=!1,this._activeTrigger.focus=!1,this._activeTrigger.hover=!1,o.default(this.tip).hasClass(Lt)){var s=d.getTransitionDurationFromElement(n);o.default(n).one(d.TRANSITION_END,a).emulateTransitionEnd(s)}else a();this._hoverState=""}},e.update=function(){null!==this._popper&&this._popper.scheduleUpdate()},e.isWithContent=function(){return Boolean(this.getTitle())},e.addAttachmentClass=function(t){o.default(this.getTipElement()).addClass("bs-tooltip-"+t)},e.getTipElement=function(){return this.tip=this.tip||o.default(this.config.template)[0],this.tip},e.setContent=function(){var t=this.getTipElement();this.setElementContent(o.default(t.querySelectorAll(".tooltip-inner")),this.getTitle()),o.default(t).removeClass("fade show")},e.setElementContent=function(t,e){"object"!=typeof e||!e.nodeType&&!e.jquery?this.config.html?(this.config.sanitize&&(e=At(e,this.config.whiteList,this.config.sanitizeFn)),t.html(e)):t.text(e):this.config.html?o.default(e).parent().is(t)||t.empty().append(e):t.text(o.default(e).text())},e.getTitle=function(){var t=this.element.getAttribute("data-original-title");return t||(t="function"==typeof this.config.title?this.config.title.call(this.element):this.config.title),t},e._getPopperConfig=function(t){var e=this;return r({},{placement:t,modifiers:{offset:this._getOffset(),flip:{behavior:this.config.fallbackPlacement},arrow:{element:".arrow"},preventOverflow:{boundariesElement:this.config.boundary}},onCreate:function(t){t.originalPlacement!==t.placement&&e._handlePopperPlacementChange(t)},onUpdate:function(t){return e._handlePopperPlacementChange(t)}},this.config.popperConfig)},e._getOffset=function(){var t=this,e={};return"function"==typeof this.config.offset?e.fn=function(e){return e.offsets=r({},e.offsets,t.config.offset(e.offsets,t.element)),e}:e.offset=this.config.offset,e},e._getContainer=function(){return!1===this.config.container?document.body:d.isElement(this.config.container)?o.default(this.config.container):o.default(document).find(this.config.container)},e._getAttachment=function(t){return Bt[t.toUpperCase()]},e._setListeners=function(){var t=this;this.config.trigger.split(" ").forEach((function(e){if("click"===e)o.default(t.element).on(t.constructor.Event.CLICK,t.config.selector,(function(e){return t.toggle(e)}));else if("manual"!==e){var n=e===Ft?t.constructor.Event.MOUSEENTER:t.constructor.Event.FOCUSIN,i=e===Ft?t.constructor.Event.MOUSELEAVE:t.constructor.Event.FOCUSOUT;o.default(t.element).on(n,t.config.selector,(function(e){return t._enter(e)})).on(i,t.config.selector,(function(e){return t._leave(e)}))}})),this._hideModalHandler=function(){t.element&&t.hide()},o.default(this.element).closest(".modal").on("hide.bs.modal",this._hideModalHandler),this.config.selector?this.config=r({},this.config,{trigger:"manual",selector:""}):this._fixTitle()},e._fixTitle=function(){var t=typeof this.element.getAttribute("data-original-title");(this.element.getAttribute("title")||"string"!==t)&&(this.element.setAttribute("data-original-title",this.element.getAttribute("title")||""),this.element.setAttribute("title",""))},e._enter=function(t,e){var n=this.constructor.DATA_KEY;(e=e||o.default(t.currentTarget).data(n))||(e=new this.constructor(t.currentTarget,this._getDelegateConfig()),o.default(t.currentTarget).data(n,e)),t&&(e._activeTrigger["focusin"===t.type?Qt:Ft]=!0),o.default(e.getTipElement()).hasClass(Rt)||e._hoverState===xt?e._hoverState=xt:(clearTimeout(e._timeout),e._hoverState=xt,e.config.delay&&e.config.delay.show?e._timeout=setTimeout((function(){e._hoverState===xt&&e.show()}),e.config.delay.show):e.show())},e._leave=function(t,e){var n=this.constructor.DATA_KEY;(e=e||o.default(t.currentTarget).data(n))||(e=new this.constructor(t.currentTarget,this._getDelegateConfig()),o.default(t.currentTarget).data(n,e)),t&&(e._activeTrigger["focusout"===t.type?Qt:Ft]=!1),e._isWithActiveTrigger()||(clearTimeout(e._timeout),e._hoverState=qt,e.config.delay&&e.config.delay.hide?e._timeout=setTimeout((function(){e._hoverState===qt&&e.hide()}),e.config.delay.hide):e.hide())},e._isWithActiveTrigger=function(){for(var t in this._activeTrigger)if(this._activeTrigger[t])return!0;return!1},e._getConfig=function(t){var e=o.default(this.element).data();return Object.keys(e).forEach((function(t){-1!==Pt.indexOf(t)&&delete e[t]})),"number"==typeof(t=r({},this.constructor.Default,e,"object"==typeof t&&t?t:{})).delay&&(t.delay={show:t.delay,hide:t.delay}),"number"==typeof t.title&&(t.title=t.title.toString()),"number"==typeof t.content&&(t.content=t.content.toString()),d.typeCheckConfig(It,t,this.constructor.DefaultType),t.sanitize&&(t.template=At(t.template,t.whiteList,t.sanitizeFn)),t},e._getDelegateConfig=function(){var t={};if(this.config)for(var e in this.config)this.constructor.Default[e]!==this.config[e]&&(t[e]=this.config[e]);return t},e._cleanTipClass=function(){var t=o.default(this.getTipElement()),e=t.attr("class").match(jt);null!==e&&e.length&&t.removeClass(e.join(""))},e._handlePopperPlacementChange=function(t){this.tip=t.instance.popper,this._cleanTipClass(),this.addAttachmentClass(this._getAttachment(t.placement))},e._fixTransition=function(){var t=this.getTipElement(),e=this.config.animation;null===t.getAttribute("x-placement")&&(o.default(t).removeClass(Lt),this.config.animation=!1,this.hide(),this.show(),this.config.animation=e)},t._jQueryInterface=function(e){return this.each((function(){var n=o.default(this),i=n.data(kt),a="object"==typeof e&&e;if((i||!/dispose|hide/.test(e))&&(i||(i=new t(this,a),n.data(kt,i)),"string"==typeof e)){if("undefined"==typeof i[e])throw new TypeError('No method named "'+e+'"');i[e]()}}))},l(t,null,[{key:"VERSION",get:function(){return"4.6.2"}},{key:"Default",get:function(){return Ht}},{key:"NAME",get:function(){return It}},{key:"DATA_KEY",get:function(){return kt}},{key:"Event",get:function(){return Mt}},{key:"EVENT_KEY",get:function(){return".bs.tooltip"}},{key:"DefaultType",get:function(){return Ut}}]),t}();o.default.fn.tooltip=Wt._jQueryInterface,o.default.fn.tooltip.Constructor=Wt,o.default.fn.tooltip.noConflict=function(){return o.default.fn.tooltip=Ot,Wt._jQueryInterface};var Vt="bs.popover",zt=o.default.fn.popover,Kt=new RegExp("(^|\\s)bs-popover\\S+","g"),Xt=r({},Wt.Default,{placement:"right",trigger:"click",content:"",template:''}),Yt=r({},Wt.DefaultType,{content:"(string|element|function)"}),$t={HIDE:"hide.bs.popover",HIDDEN:"hidden.bs.popover",SHOW:"show.bs.popover",SHOWN:"shown.bs.popover",INSERTED:"inserted.bs.popover",CLICK:"click.bs.popover",FOCUSIN:"focusin.bs.popover",FOCUSOUT:"focusout.bs.popover",MOUSEENTER:"mouseenter.bs.popover",MOUSELEAVE:"mouseleave.bs.popover"},Jt=function(t){var e,n;function i(){return t.apply(this,arguments)||this}n=t,(e=i).prototype=Object.create(n.prototype),e.prototype.constructor=e,u(e,n);var a=i.prototype;return a.isWithContent=function(){return this.getTitle()||this._getContent()},a.addAttachmentClass=function(t){o.default(this.getTipElement()).addClass("bs-popover-"+t)},a.getTipElement=function(){return this.tip=this.tip||o.default(this.config.template)[0],this.tip},a.setContent=function(){var t=o.default(this.getTipElement());this.setElementContent(t.find(".popover-header"),this.getTitle());var e=this._getContent();"function"==typeof e&&(e=e.call(this.element)),this.setElementContent(t.find(".popover-body"),e),t.removeClass("fade show")},a._getContent=function(){return this.element.getAttribute("data-content")||this.config.content},a._cleanTipClass=function(){var t=o.default(this.getTipElement()),e=t.attr("class").match(Kt);null!==e&&e.length>0&&t.removeClass(e.join(""))},i._jQueryInterface=function(t){return this.each((function(){var e=o.default(this).data(Vt),n="object"==typeof t?t:null;if((e||!/dispose|hide/.test(t))&&(e||(e=new i(this,n),o.default(this).data(Vt,e)),"string"==typeof t)){if("undefined"==typeof e[t])throw new TypeError('No method named "'+t+'"');e[t]()}}))},l(i,null,[{key:"VERSION",get:function(){return"4.6.2"}},{key:"Default",get:function(){return Xt}},{key:"NAME",get:function(){return"popover"}},{key:"DATA_KEY",get:function(){return Vt}},{key:"Event",get:function(){return $t}},{key:"EVENT_KEY",get:function(){return".bs.popover"}},{key:"DefaultType",get:function(){return Yt}}]),i}(Wt);o.default.fn.popover=Jt._jQueryInterface,o.default.fn.popover.Constructor=Jt,o.default.fn.popover.noConflict=function(){return o.default.fn.popover=zt,Jt._jQueryInterface};var Gt="scrollspy",Zt="bs.scrollspy",te=o.default.fn[Gt],ee="active",ne="position",ie=".nav, .list-group",oe={offset:10,method:"auto",target:""},ae={offset:"number",method:"string",target:"(string|element)"},se=function(){function t(t,e){var n=this;this._element=t,this._scrollElement="BODY"===t.tagName?window:t,this._config=this._getConfig(e),this._selector=this._config.target+" .nav-link,"+this._config.target+" .list-group-item,"+this._config.target+" .dropdown-item",this._offsets=[],this._targets=[],this._activeTarget=null,this._scrollHeight=0,o.default(this._scrollElement).on("scroll.bs.scrollspy",(function(t){return n._process(t)})),this.refresh(),this._process()}var e=t.prototype;return e.refresh=function(){var t=this,e=this._scrollElement===this._scrollElement.window?"offset":ne,n="auto"===this._config.method?e:this._config.method,i=n===ne?this._getScrollTop():0;this._offsets=[],this._targets=[],this._scrollHeight=this._getScrollHeight(),[].slice.call(document.querySelectorAll(this._selector)).map((function(t){var e,a=d.getSelectorFromElement(t);if(a&&(e=document.querySelector(a)),e){var s=e.getBoundingClientRect();if(s.width||s.height)return[o.default(e)[n]().top+i,a]}return null})).filter(Boolean).sort((function(t,e){return t[0]-e[0]})).forEach((function(e){t._offsets.push(e[0]),t._targets.push(e[1])}))},e.dispose=function(){o.default.removeData(this._element,Zt),o.default(this._scrollElement).off(".bs.scrollspy"),this._element=null,this._scrollElement=null,this._config=null,this._selector=null,this._offsets=null,this._targets=null,this._activeTarget=null,this._scrollHeight=null},e._getConfig=function(t){if("string"!=typeof(t=r({},oe,"object"==typeof t&&t?t:{})).target&&d.isElement(t.target)){var e=o.default(t.target).attr("id");e||(e=d.getUID(Gt),o.default(t.target).attr("id",e)),t.target="#"+e}return d.typeCheckConfig(Gt,t,ae),t},e._getScrollTop=function(){return this._scrollElement===window?this._scrollElement.pageYOffset:this._scrollElement.scrollTop},e._getScrollHeight=function(){return this._scrollElement.scrollHeight||Math.max(document.body.scrollHeight,document.documentElement.scrollHeight)},e._getOffsetHeight=function(){return this._scrollElement===window?window.innerHeight:this._scrollElement.getBoundingClientRect().height},e._process=function(){var t=this._getScrollTop()+this._config.offset,e=this._getScrollHeight(),n=this._config.offset+e-this._getOffsetHeight();if(this._scrollHeight!==e&&this.refresh(),t>=n){var i=this._targets[this._targets.length-1];this._activeTarget!==i&&this._activate(i)}else{if(this._activeTarget&&t0)return this._activeTarget=null,void this._clear();for(var o=this._offsets.length;o--;)this._activeTarget!==this._targets[o]&&t>=this._offsets[o]&&("undefined"==typeof this._offsets[o+1]||t li > .active",ge=function(){function t(t){this._element=t}var e=t.prototype;return e.show=function(){var t=this;if(!(this._element.parentNode&&this._element.parentNode.nodeType===Node.ELEMENT_NODE&&o.default(this._element).hasClass(ue)||o.default(this._element).hasClass("disabled")||this._element.hasAttribute("disabled"))){var e,n,i=o.default(this._element).closest(".nav, .list-group")[0],a=d.getSelectorFromElement(this._element);if(i){var s="UL"===i.nodeName||"OL"===i.nodeName?he:ce;n=(n=o.default.makeArray(o.default(i).find(s)))[n.length-1]}var l=o.default.Event("hide.bs.tab",{relatedTarget:this._element}),r=o.default.Event("show.bs.tab",{relatedTarget:n});if(n&&o.default(n).trigger(l),o.default(this._element).trigger(r),!r.isDefaultPrevented()&&!l.isDefaultPrevented()){a&&(e=document.querySelector(a)),this._activate(this._element,i);var u=function(){var e=o.default.Event("hidden.bs.tab",{relatedTarget:t._element}),i=o.default.Event("shown.bs.tab",{relatedTarget:n});o.default(n).trigger(e),o.default(t._element).trigger(i)};e?this._activate(e,e.parentNode,u):u()}}},e.dispose=function(){o.default.removeData(this._element,le),this._element=null},e._activate=function(t,e,n){var i=this,a=(!e||"UL"!==e.nodeName&&"OL"!==e.nodeName?o.default(e).children(ce):o.default(e).find(he))[0],s=n&&a&&o.default(a).hasClass(fe),l=function(){return i._transitionComplete(t,a,n)};if(a&&s){var r=d.getTransitionDurationFromElement(a);o.default(a).removeClass(de).one(d.TRANSITION_END,l).emulateTransitionEnd(r)}else l()},e._transitionComplete=function(t,e,n){if(e){o.default(e).removeClass(ue);var i=o.default(e.parentNode).find("> .dropdown-menu .active")[0];i&&o.default(i).removeClass(ue),"tab"===e.getAttribute("role")&&e.setAttribute("aria-selected",!1)}o.default(t).addClass(ue),"tab"===t.getAttribute("role")&&t.setAttribute("aria-selected",!0),d.reflow(t),t.classList.contains(fe)&&t.classList.add(de);var a=t.parentNode;if(a&&"LI"===a.nodeName&&(a=a.parentNode),a&&o.default(a).hasClass("dropdown-menu")){var s=o.default(t).closest(".dropdown")[0];if(s){var l=[].slice.call(s.querySelectorAll(".dropdown-toggle"));o.default(l).addClass(ue)}t.setAttribute("aria-expanded",!0)}n&&n()},t._jQueryInterface=function(e){return this.each((function(){var n=o.default(this),i=n.data(le);if(i||(i=new t(this),n.data(le,i)),"string"==typeof e){if("undefined"==typeof i[e])throw new TypeError('No method named "'+e+'"');i[e]()}}))},l(t,null,[{key:"VERSION",get:function(){return"4.6.2"}}]),t}();o.default(document).on("click.bs.tab.data-api",'[data-toggle="tab"], [data-toggle="pill"], [data-toggle="list"]',(function(t){t.preventDefault(),ge._jQueryInterface.call(o.default(this),"show")})),o.default.fn.tab=ge._jQueryInterface,o.default.fn.tab.Constructor=ge,o.default.fn.tab.noConflict=function(){return o.default.fn.tab=re,ge._jQueryInterface};var me="bs.toast",pe=o.default.fn.toast,_e="hide",ve="show",ye="showing",be="click.dismiss.bs.toast",Ee={animation:!0,autohide:!0,delay:500},Te={animation:"boolean",autohide:"boolean",delay:"number"},we=function(){function t(t,e){this._element=t,this._config=this._getConfig(e),this._timeout=null,this._setListeners()}var e=t.prototype;return e.show=function(){var t=this,e=o.default.Event("show.bs.toast");if(o.default(this._element).trigger(e),!e.isDefaultPrevented()){this._clearTimeout(),this._config.animation&&this._element.classList.add("fade");var n=function(){t._element.classList.remove(ye),t._element.classList.add(ve),o.default(t._element).trigger("shown.bs.toast"),t._config.autohide&&(t._timeout=setTimeout((function(){t.hide()}),t._config.delay))};if(this._element.classList.remove(_e),d.reflow(this._element),this._element.classList.add(ye),this._config.animation){var i=d.getTransitionDurationFromElement(this._element);o.default(this._element).one(d.TRANSITION_END,n).emulateTransitionEnd(i)}else n()}},e.hide=function(){if(this._element.classList.contains(ve)){var t=o.default.Event("hide.bs.toast");o.default(this._element).trigger(t),t.isDefaultPrevented()||this._close()}},e.dispose=function(){this._clearTimeout(),this._element.classList.contains(ve)&&this._element.classList.remove(ve),o.default(this._element).off(be),o.default.removeData(this._element,me),this._element=null,this._config=null},e._getConfig=function(t){return t=r({},Ee,o.default(this._element).data(),"object"==typeof t&&t?t:{}),d.typeCheckConfig("toast",t,this.constructor.DefaultType),t},e._setListeners=function(){var t=this;o.default(this._element).on(be,'[data-dismiss="toast"]',(function(){return t.hide()}))},e._close=function(){var t=this,e=function(){t._element.classList.add(_e),o.default(t._element).trigger("hidden.bs.toast")};if(this._element.classList.remove(ve),this._config.animation){var n=d.getTransitionDurationFromElement(this._element);o.default(this._element).one(d.TRANSITION_END,e).emulateTransitionEnd(n)}else e()},e._clearTimeout=function(){clearTimeout(this._timeout),this._timeout=null},t._jQueryInterface=function(e){return this.each((function(){var n=o.default(this),i=n.data(me);if(i||(i=new t(this,"object"==typeof e&&e),n.data(me,i)),"string"==typeof e){if("undefined"==typeof i[e])throw new TypeError('No method named "'+e+'"');i[e](this)}}))},l(t,null,[{key:"VERSION",get:function(){return"4.6.2"}},{key:"DefaultType",get:function(){return Te}},{key:"Default",get:function(){return Ee}}]),t}();o.default.fn.toast=we._jQueryInterface,o.default.fn.toast.Constructor=we,o.default.fn.toast.noConflict=function(){return o.default.fn.toast=pe,we._jQueryInterface},t.Alert=g,t.Button=E,t.Carousel=P,t.Collapse=V,t.Dropdown=lt,t.Modal=Ct,t.Popover=Jt,t.Scrollspy=se,t.Tab=ge,t.Toast=we,t.Tooltip=Wt,t.Util=d,Object.defineProperty(t,"__esModule",{value:!0})})); +//# sourceMappingURL=bootstrap.min.js.map diff --git a/mobile_manipulator/ifarlab_web/js/eventemitter2.min.js b/mobile_manipulator/ifarlab_web/js/eventemitter2.min.js new file mode 100644 index 0000000..b907554 --- /dev/null +++ b/mobile_manipulator/ifarlab_web/js/eventemitter2.min.js @@ -0,0 +1 @@ +!function(e){function t(){this._events={},this._conf&&i.call(this,this._conf)}function i(e){e&&(this._conf=e,e.delimiter&&(this.delimiter=e.delimiter),e.maxListeners&&(this._events.maxListeners=e.maxListeners),e.wildcard&&(this.wildcard=e.wildcard),e.newListener&&(this.newListener=e.newListener),this.wildcard&&(this.listenerTree={}))}function s(e){this._events={},this.newListener=!1,i.call(this,e)}function n(e,t,i,s){if(!i)return[];var r,l,o,h,a,f,c,_=[],p=t.length,u=t[s],v=t[s+1];if(s===p&&i._listeners){if("function"==typeof i._listeners)return e&&e.push(i._listeners),[i];for(r=0,l=i._listeners.length;r0&&n._listeners.length>h&&(n._listeners.warned=!0,console.error("(node) warning: possible EventEmitter memory leak detected. %d listeners added. Use emitter.setMaxListeners() to increase limit.",n._listeners.length),console.trace())}}else n._listeners=t;return!0}r=e.shift()}return!0}var l=Array.isArray?Array.isArray:function(e){return"[object Array]"===Object.prototype.toString.call(e)},o=10;s.prototype.delimiter=".",s.prototype.setMaxListeners=function(e){this._events||t.call(this),this._events.maxListeners=e,this._conf||(this._conf={}),this._conf.maxListeners=e},s.prototype.event="",s.prototype.once=function(e,t){return this.many(e,1,t),this},s.prototype.many=function(e,t,i){function s(){0==--t&&n.off(e,s),i.apply(this,arguments)}var n=this;if("function"!=typeof i)throw new Error("many only accepts instances of Function");return s._origin=i,this.on(e,s),n},s.prototype.emit=function(){this._events||t.call(this);var e=arguments[0];if("newListener"===e&&!this.newListener&&!this._events.newListener)return!1;if(this._all){for(var i=arguments.length,s=new Array(i-1),r=1;r1)switch(arguments.length){case 2:l.call(this,arguments[1]);break;case 3:l.call(this,arguments[1],arguments[2]);break;default:for(var i=arguments.length,s=new Array(i-1),r=1;r0||!!this._all}return!!this._all},s.prototype.on=function(e,i){if("function"==typeof e)return this.onAny(e),this;if("function"!=typeof i)throw new Error("on only accepts instances of Function");if(this._events||t.call(this),this.emit("newListener",e,i),this.wildcard)return r.call(this,e,i),this;if(this._events[e]){if("function"==typeof this._events[e])this._events[e]=[this._events[e],i];else if(l(this._events[e])&&(this._events[e].push(i),!this._events[e].warned)){var s=o;void 0!==this._events.maxListeners&&(s=this._events.maxListeners),s>0&&this._events[e].length>s&&(this._events[e].warned=!0,console.error("(node) warning: possible EventEmitter memory leak detected. %d listeners added. Use emitter.setMaxListeners() to increase limit.",this._events[e].length),console.trace())}}else this._events[e]=i;return this},s.prototype.onAny=function(e){if("function"!=typeof e)throw new Error("onAny only accepts instances of Function");return this._all||(this._all=[]),this._all.push(e),this},s.prototype.addListener=s.prototype.on,s.prototype.off=function(e,t){if("function"!=typeof t)throw new Error("removeListener only takes instances of Function");var i,s=[];if(this.wildcard){var r="string"==typeof e?e.split(this.delimiter):e.slice();s=n.call(this,null,r,this.listenerTree,0)}else{if(!this._events[e])return this;i=this._events[e],s.push({_listeners:i})}for(var o=0;o0){for(i=0,s=(t=this._all).length;i element that closes the modal +var span = document.getElementsByClassName("close")[0]; + +// When the user clicks the button, open the modal +btn.onclick = function () { + emgmodal.style.display = "block"; + emg_stop(); +} + +// When the user clicks on (x), close the modal +span.onclick = function () { + emgmodal.style.display = "none"; +} + +// When the user clicks anywhere outside of the modal, close it +window.onclick = function (event) { + if (event.target == emgmodal) { + emgmodal.style.display = "none"; + } +} + +// Connecting to ROS +// ----------------- + + // Connect to ROS. +ros = new ROSLIB.Ros({ + url: 'ws://localhost:9090' +}); + + + +let testBool = 0; + +ros.on('connection', function () { + console.log("Connected to websocket server") + isConnected=true; +}) ; + +ros.on('close', function (error) { +console.log("Close connecting to websocket server:", error); +isConnected=false +commodal.style.display = "block"; +}); + +ros.on('error', function (error) { + console.log("Error connecting to websocket server:", error); + isConnected=false + commodal.style.display = "block"; + +}); + + + +var ui_start_button = 0; + +// Publishing a Topic +// ------------------ + +var ui_start = new ROSLIB.Topic({ + ros: ros, + name: '/ui_start', + messageType: 'std_msgs/Int8' +}); + +var ui_emg_stop = new ROSLIB.Topic({ + ros: ros, + name: '/ui_emg', + messageType: 'std_msgs/Int8' +}); + +var emg_sub = new ROSLIB.Topic({ + ros: ros, + name: '/emg', + messageType: 'std_msgs/Int8' +}); + +var ui_start = new ROSLIB.Topic({ + ros: ros, + name: '/ui_start', + messageType: 'std_msgs/Int8' +}); + +var ui_status = new ROSLIB.Topic({ + ros: ros, + name: '/ui_task_status', + messageType: 'std_msgs/String' +}); + +var mobile_status_topic = new ROSLIB.Topic({ + ros: ros, + name: '/mobile_status', + messageType: 'std_msgs/String' +}); + +function start() { + ui_start_button = 1; + var ui_start_data = new ROSLIB.Message({ + data: ui_start_button + }); + + console.log(ui_start_button) + ui_start.publish(ui_start_data); + // +} + +function emg_stop() { + var emg_stop_data = new ROSLIB.Message({ + data: 1 + }); + + ui_emg_stop.publish(emg_stop_data); +} + +document.getElementById("mr_motion").style.pointerEvents = "none"; +document.getElementById("mr_motion").style.opacity = 0.5; + +ui_status_flag = false +ui_status.subscribe(function (message) { + let text = (message.data).replace(/['"]+/g, '"'); + json_data = JSON.parse(text); + task_status_data = json_data.task_status + active_id_data = json_data.active_id + // console.log(json_data) + document.getElementById("task_status").value = task_status_data; + document.getElementById("task_id").value = active_id_data; + if (task_status_data.includes("Manuel")){ + if (!ui_status_flag){ + testBool = 1 + document.getElementById("mr_motion").style.pointerEvents = "auto"; + document.getElementById("mr_motion").style.opacity = 1.0; + document.getElementById("tasktracking").style.pointerEvents = "none"; + document.getElementById("tasktracking").style.opacity = 0.5; + document.getElementById("toggle-button").checked = true; + ui_status_flag = true + } + } + else{ + if (ui_status_flag){ + testBool = 0 + document.getElementById("mr_motion").style.pointerEvents = "none"; + document.getElementById("mr_motion").style.opacity = 0.5; + document.getElementById("toggle-button").checked = false; + document.getElementById("tasktracking").style.pointerEvents = "auto"; + document.getElementById("tasktracking").style.opacity = 1.0; + ui_status_flag = false + } + } +}); + +ui_emg_stop.subscribe(function (message) { + console.log(message.data) + if (message.data == 1) { + emgmodal.style.display = "block"; + } + else { + emgmodal.style.display = "none"; + } +}); + +emg_sub.subscribe(function (message) { + if (message.data == 1) { + if (emgmodal.style.display == "none"){ + emgmodal.style.display = "block"; + } + } +}); + +mobile_status_topic.subscribe(function (message) { + document.getElementById("text_mr_status").value = message.data; +}); +// Calling a service +// ----------------- + +var addTwoIntsClient = new ROSLIB.Service({ + ros: ros, + name: '/right_rokos_task_service', + serviceType: 'srvt_moveit/TaskService' +}); + +addTwoIntsClient.callService(" ", function (result) { + var task_list = [] + let list = document.getElementById("tasklist"); + console.log('Result for service call on ' + + addTwoIntsClient.name + + ': ' + + result.response); + var myJSON = eval(eval(JSON.stringify(result.response))); + for (let x of myJSON) { + task_list.push(x[x.length - 1][0]) + let li = document.createElement("li"); + li.innerText = x[x.length - 1][0]; + list.appendChild(li); + } + console.log(task_list) + +}); + +var odom_sub = new ROSLIB.Topic({ + ros: ros, + name: '/odom', + messageType: 'nav_msgs/Odometry' +}); + +var cmdVel = new ROSLIB.Topic({ + ros: ros, + name: '/cmd_vel', + messageType: 'geometry_msgs/Twist' +}); + +var toggle_option = new ROSLIB.Topic({ + ros: ros, + name: '/toggle', + messageType: 'std_msgs/Int8' +}); + +var ui_params = new ROSLIB.Topic({ + ros: ros, + name: '/ui_parameters_topic', + messageType: 'std_msgs/String' +}); + +var ui_set_params = new ROSLIB.Topic({ + ros: ros, + name: '/ui_set_parameters', + messageType: 'std_msgs/String' +}); + +var ui_stop = new ROSLIB.Topic({ + ros: ros, + name: '/manuel_stop', + messageType: 'std_msgs/Int8' +}); + +var ui_vel = new ROSLIB.Topic({ + ros: ros, + name: '/manuel_vel', + messageType: 'std_msgs/Int8' +}); + + + +var twist = new ROSLIB.Message({ + linear: { + x: 0.0, + y: 0.0, + z: 0.0 + }, + angular: { + x: 0.0, + y: 0.0, + z: 0.0 + } +}); + +var ui_stop_data = new ROSLIB.Message({ + data: 1 +}); + +var ui_vel_data = new ROSLIB.Message({ + data: 0 +}); + +function manipulator_stop(){ + ui_vel_data.data = 1; + ui_stop.publish(ui_vel_data) +} + +function manipulator_release(){ + ui_vel_data.data = 2; + ui_stop.publish(ui_vel_data) +} + +function move_forward() { + + twist.linear.x = parseFloat(document.getElementById("mr_ui_velocity").value); + ui_vel_data.data = 1; + ui_vel.publish(ui_vel_data); + + // twist.angular.z = 0.0; + // cmdVel.publish(twist); +} + +function move_backward() { + ui_vel_data.data = -1; + ui_vel.publish(ui_vel_data); + + twist.linear.x = -1 * parseFloat(document.getElementById("mr_ui_velocity").value); + // twist.angular.z = 0.0; + // cmdVel.publish(twist); +} + +function move_stop() { + ui_vel_data.data = 0; + ui_vel.publish(ui_vel_data); + // twist.linear.x = 0.0; + // twist.angular.z = 0.0; + // cmdVel.publish(twist); +} + +odom_sub.subscribe(function (message) { + document.getElementById("text_mr_postion").value = (message.pose.pose.position.x).toFixed(2); + document.getElementById("text_mr_velocity").value = (message.twist.twist.linear.x).toFixed(2); +}); + +ui_params.subscribe(function (message) { + let text = (message.data).replace(/['"]+/g, '"'); + json_data = JSON.parse(text); + // document.getElementById("mr_ui_rate").value = json_data.topic_rate; + document.getElementById("mr_ui_velocity").value = json_data.robot_velocity; + // document.getElementById("mr_ui_origin").value = json_data.sensor_origin_set; + ui_params.unsubscribe(); + + +}); + +var light_curtain = new ROSLIB.Topic({ + ros: ros, + name: '/light_curtain', + messageType: 'std_msgs/Bool' +}); + +light_curtain.subscribe(function (message) { + if (message.data == true){ + var emg_stop_data = new ROSLIB.Message({ + data: 1 + }); + + ui_emg_stop.publish(emg_stop_data); + } +}); + + + + +var emg_continue_btn = document.getElementById("emergency_continue"); + +// When the user clicks the button, open the modal +emg_continue_btn.onclick = function () { + emgmodal.style.display = "none"; + var emg_stop_data = new ROSLIB.Message({ + data: 0 + }); + for (let i = 0; i < 5; i++) { + ui_emg_stop.publish(emg_stop_data); + } +} + +// document.getElementById("mr_ui_rate").value = 10; +// document.getElementById("mr_ui_velocity").value = 0.1; +// document.getElementById("mr_ui_origin").value = 2.5; + + +var config_btn = document.getElementById("config_button"); + +config_btn.onclick = function () { + // let rate = document.getElementById("mr_ui_rate").value; + let vel = document.getElementById("mr_ui_velocity").value; + // let origin = document.getElementById("mr_ui_origin").value; + str_data = "{\"topic_rate\":50" + ",\"robot_velocity\":" + vel + ",\"sensor_origin_set\":2.5}"; + + var config_data = new ROSLIB.Message({ + data: str_data + }); + ui_set_params.publish(config_data) +} + +function toggle() { + testBool = !testBool; + if (testBool == false){ + testBool = 0;} + else{ + testBool = 1; + } + var toggle_msg = new ROSLIB.Message({ + data: testBool + }); + toggle_option.publish(toggle_msg) + if(testBool){ + document.getElementById("tasktracking").style.pointerEvents = "none"; + document.getElementById("tasktracking").style.opacity = 0.5; + document.getElementById("mr_motion").style.pointerEvents = "auto"; + document.getElementById("mr_motion").style.opacity = 1.0; + } + else{ + document.getElementById("tasktracking").style.pointerEvents = "auto"; + document.getElementById("tasktracking").style.opacity = 1.0; + document.getElementById("mr_motion").style.pointerEvents = "none"; + document.getElementById("mr_motion").style.opacity = 0.5; + } + } + + + + +/********************************/ +// function connectRos() { + +// ros.on('connection', function () { +// console.log("Connected to websocket server") +// isConnected=true; +// }) ; +// ros.on('close', function (error) { +// console.log("Close connecting to websocket server:", error); +// isConnected=false +// }); +// ros.on('error', function (error) { +// console.log("Error connecting to websocket server:", error); +// isConnected=false +// }); +// } + +// $(document).ready(function() { +// connectRos(); +// setInterval(checkConnection,1000); +// }); + +// function checkConnection(){ +// if(isConnected===false) +// connectRos(); +// } \ No newline at end of file diff --git a/mobile_manipulator/ifarlab_web/js/jquery.min.js b/mobile_manipulator/ifarlab_web/js/jquery.min.js new file mode 100644 index 0000000..b061403 --- /dev/null +++ b/mobile_manipulator/ifarlab_web/js/jquery.min.js @@ -0,0 +1,2 @@ +/*! jQuery v3.5.1 | (c) JS Foundation and other contributors | jquery.org/license */ +!function(e,t){"use strict";"object"==typeof module&&"object"==typeof module.exports?module.exports=e.document?t(e,!0):function(e){if(!e.document)throw new Error("jQuery requires a window with a document");return t(e)}:t(e)}("undefined"!=typeof window?window:this,function(C,e){"use strict";var t=[],r=Object.getPrototypeOf,s=t.slice,g=t.flat?function(e){return t.flat.call(e)}:function(e){return t.concat.apply([],e)},u=t.push,i=t.indexOf,n={},o=n.toString,v=n.hasOwnProperty,a=v.toString,l=a.call(Object),y={},m=function(e){return"function"==typeof e&&"number"!=typeof e.nodeType},x=function(e){return null!=e&&e===e.window},E=C.document,c={type:!0,src:!0,nonce:!0,noModule:!0};function b(e,t,n){var r,i,o=(n=n||E).createElement("script");if(o.text=e,t)for(r in c)(i=t[r]||t.getAttribute&&t.getAttribute(r))&&o.setAttribute(r,i);n.head.appendChild(o).parentNode.removeChild(o)}function w(e){return null==e?e+"":"object"==typeof e||"function"==typeof e?n[o.call(e)]||"object":typeof e}var f="3.5.1",S=function(e,t){return new S.fn.init(e,t)};function p(e){var t=!!e&&"length"in e&&e.length,n=w(e);return!m(e)&&!x(e)&&("array"===n||0===t||"number"==typeof t&&0+~]|"+M+")"+M+"*"),U=new RegExp(M+"|>"),X=new RegExp(F),V=new RegExp("^"+I+"$"),G={ID:new RegExp("^#("+I+")"),CLASS:new RegExp("^\\.("+I+")"),TAG:new RegExp("^("+I+"|[*])"),ATTR:new RegExp("^"+W),PSEUDO:new RegExp("^"+F),CHILD:new RegExp("^:(only|first|last|nth|nth-last)-(child|of-type)(?:\\("+M+"*(even|odd|(([+-]|)(\\d*)n|)"+M+"*(?:([+-]|)"+M+"*(\\d+)|))"+M+"*\\)|)","i"),bool:new RegExp("^(?:"+R+")$","i"),needsContext:new RegExp("^"+M+"*[>+~]|:(even|odd|eq|gt|lt|nth|first|last)(?:\\("+M+"*((?:-\\d)?\\d*)"+M+"*\\)|)(?=[^-]|$)","i")},Y=/HTML$/i,Q=/^(?:input|select|textarea|button)$/i,J=/^h\d$/i,K=/^[^{]+\{\s*\[native \w/,Z=/^(?:#([\w-]+)|(\w+)|\.([\w-]+))$/,ee=/[+~]/,te=new RegExp("\\\\[\\da-fA-F]{1,6}"+M+"?|\\\\([^\\r\\n\\f])","g"),ne=function(e,t){var n="0x"+e.slice(1)-65536;return t||(n<0?String.fromCharCode(n+65536):String.fromCharCode(n>>10|55296,1023&n|56320))},re=/([\0-\x1f\x7f]|^-?\d)|^-$|[^\0-\x1f\x7f-\uFFFF\w-]/g,ie=function(e,t){return t?"\0"===e?"\ufffd":e.slice(0,-1)+"\\"+e.charCodeAt(e.length-1).toString(16)+" ":"\\"+e},oe=function(){T()},ae=be(function(e){return!0===e.disabled&&"fieldset"===e.nodeName.toLowerCase()},{dir:"parentNode",next:"legend"});try{H.apply(t=O.call(p.childNodes),p.childNodes),t[p.childNodes.length].nodeType}catch(e){H={apply:t.length?function(e,t){L.apply(e,O.call(t))}:function(e,t){var n=e.length,r=0;while(e[n++]=t[r++]);e.length=n-1}}}function se(t,e,n,r){var i,o,a,s,u,l,c,f=e&&e.ownerDocument,p=e?e.nodeType:9;if(n=n||[],"string"!=typeof t||!t||1!==p&&9!==p&&11!==p)return n;if(!r&&(T(e),e=e||C,E)){if(11!==p&&(u=Z.exec(t)))if(i=u[1]){if(9===p){if(!(a=e.getElementById(i)))return n;if(a.id===i)return n.push(a),n}else if(f&&(a=f.getElementById(i))&&y(e,a)&&a.id===i)return n.push(a),n}else{if(u[2])return H.apply(n,e.getElementsByTagName(t)),n;if((i=u[3])&&d.getElementsByClassName&&e.getElementsByClassName)return H.apply(n,e.getElementsByClassName(i)),n}if(d.qsa&&!N[t+" "]&&(!v||!v.test(t))&&(1!==p||"object"!==e.nodeName.toLowerCase())){if(c=t,f=e,1===p&&(U.test(t)||z.test(t))){(f=ee.test(t)&&ye(e.parentNode)||e)===e&&d.scope||((s=e.getAttribute("id"))?s=s.replace(re,ie):e.setAttribute("id",s=S)),o=(l=h(t)).length;while(o--)l[o]=(s?"#"+s:":scope")+" "+xe(l[o]);c=l.join(",")}try{return H.apply(n,f.querySelectorAll(c)),n}catch(e){N(t,!0)}finally{s===S&&e.removeAttribute("id")}}}return g(t.replace($,"$1"),e,n,r)}function ue(){var r=[];return function e(t,n){return r.push(t+" ")>b.cacheLength&&delete e[r.shift()],e[t+" "]=n}}function le(e){return e[S]=!0,e}function ce(e){var t=C.createElement("fieldset");try{return!!e(t)}catch(e){return!1}finally{t.parentNode&&t.parentNode.removeChild(t),t=null}}function fe(e,t){var n=e.split("|"),r=n.length;while(r--)b.attrHandle[n[r]]=t}function pe(e,t){var n=t&&e,r=n&&1===e.nodeType&&1===t.nodeType&&e.sourceIndex-t.sourceIndex;if(r)return r;if(n)while(n=n.nextSibling)if(n===t)return-1;return e?1:-1}function de(t){return function(e){return"input"===e.nodeName.toLowerCase()&&e.type===t}}function he(n){return function(e){var t=e.nodeName.toLowerCase();return("input"===t||"button"===t)&&e.type===n}}function ge(t){return function(e){return"form"in e?e.parentNode&&!1===e.disabled?"label"in e?"label"in e.parentNode?e.parentNode.disabled===t:e.disabled===t:e.isDisabled===t||e.isDisabled!==!t&&ae(e)===t:e.disabled===t:"label"in e&&e.disabled===t}}function ve(a){return le(function(o){return o=+o,le(function(e,t){var n,r=a([],e.length,o),i=r.length;while(i--)e[n=r[i]]&&(e[n]=!(t[n]=e[n]))})})}function ye(e){return e&&"undefined"!=typeof e.getElementsByTagName&&e}for(e in d=se.support={},i=se.isXML=function(e){var t=e.namespaceURI,n=(e.ownerDocument||e).documentElement;return!Y.test(t||n&&n.nodeName||"HTML")},T=se.setDocument=function(e){var t,n,r=e?e.ownerDocument||e:p;return r!=C&&9===r.nodeType&&r.documentElement&&(a=(C=r).documentElement,E=!i(C),p!=C&&(n=C.defaultView)&&n.top!==n&&(n.addEventListener?n.addEventListener("unload",oe,!1):n.attachEvent&&n.attachEvent("onunload",oe)),d.scope=ce(function(e){return a.appendChild(e).appendChild(C.createElement("div")),"undefined"!=typeof e.querySelectorAll&&!e.querySelectorAll(":scope fieldset div").length}),d.attributes=ce(function(e){return e.className="i",!e.getAttribute("className")}),d.getElementsByTagName=ce(function(e){return e.appendChild(C.createComment("")),!e.getElementsByTagName("*").length}),d.getElementsByClassName=K.test(C.getElementsByClassName),d.getById=ce(function(e){return a.appendChild(e).id=S,!C.getElementsByName||!C.getElementsByName(S).length}),d.getById?(b.filter.ID=function(e){var t=e.replace(te,ne);return function(e){return e.getAttribute("id")===t}},b.find.ID=function(e,t){if("undefined"!=typeof t.getElementById&&E){var n=t.getElementById(e);return n?[n]:[]}}):(b.filter.ID=function(e){var n=e.replace(te,ne);return function(e){var t="undefined"!=typeof e.getAttributeNode&&e.getAttributeNode("id");return t&&t.value===n}},b.find.ID=function(e,t){if("undefined"!=typeof t.getElementById&&E){var n,r,i,o=t.getElementById(e);if(o){if((n=o.getAttributeNode("id"))&&n.value===e)return[o];i=t.getElementsByName(e),r=0;while(o=i[r++])if((n=o.getAttributeNode("id"))&&n.value===e)return[o]}return[]}}),b.find.TAG=d.getElementsByTagName?function(e,t){return"undefined"!=typeof t.getElementsByTagName?t.getElementsByTagName(e):d.qsa?t.querySelectorAll(e):void 0}:function(e,t){var n,r=[],i=0,o=t.getElementsByTagName(e);if("*"===e){while(n=o[i++])1===n.nodeType&&r.push(n);return r}return o},b.find.CLASS=d.getElementsByClassName&&function(e,t){if("undefined"!=typeof t.getElementsByClassName&&E)return t.getElementsByClassName(e)},s=[],v=[],(d.qsa=K.test(C.querySelectorAll))&&(ce(function(e){var t;a.appendChild(e).innerHTML="",e.querySelectorAll("[msallowcapture^='']").length&&v.push("[*^$]="+M+"*(?:''|\"\")"),e.querySelectorAll("[selected]").length||v.push("\\["+M+"*(?:value|"+R+")"),e.querySelectorAll("[id~="+S+"-]").length||v.push("~="),(t=C.createElement("input")).setAttribute("name",""),e.appendChild(t),e.querySelectorAll("[name='']").length||v.push("\\["+M+"*name"+M+"*="+M+"*(?:''|\"\")"),e.querySelectorAll(":checked").length||v.push(":checked"),e.querySelectorAll("a#"+S+"+*").length||v.push(".#.+[+~]"),e.querySelectorAll("\\\f"),v.push("[\\r\\n\\f]")}),ce(function(e){e.innerHTML="";var t=C.createElement("input");t.setAttribute("type","hidden"),e.appendChild(t).setAttribute("name","D"),e.querySelectorAll("[name=d]").length&&v.push("name"+M+"*[*^$|!~]?="),2!==e.querySelectorAll(":enabled").length&&v.push(":enabled",":disabled"),a.appendChild(e).disabled=!0,2!==e.querySelectorAll(":disabled").length&&v.push(":enabled",":disabled"),e.querySelectorAll("*,:x"),v.push(",.*:")})),(d.matchesSelector=K.test(c=a.matches||a.webkitMatchesSelector||a.mozMatchesSelector||a.oMatchesSelector||a.msMatchesSelector))&&ce(function(e){d.disconnectedMatch=c.call(e,"*"),c.call(e,"[s!='']:x"),s.push("!=",F)}),v=v.length&&new RegExp(v.join("|")),s=s.length&&new RegExp(s.join("|")),t=K.test(a.compareDocumentPosition),y=t||K.test(a.contains)?function(e,t){var n=9===e.nodeType?e.documentElement:e,r=t&&t.parentNode;return e===r||!(!r||1!==r.nodeType||!(n.contains?n.contains(r):e.compareDocumentPosition&&16&e.compareDocumentPosition(r)))}:function(e,t){if(t)while(t=t.parentNode)if(t===e)return!0;return!1},D=t?function(e,t){if(e===t)return l=!0,0;var n=!e.compareDocumentPosition-!t.compareDocumentPosition;return n||(1&(n=(e.ownerDocument||e)==(t.ownerDocument||t)?e.compareDocumentPosition(t):1)||!d.sortDetached&&t.compareDocumentPosition(e)===n?e==C||e.ownerDocument==p&&y(p,e)?-1:t==C||t.ownerDocument==p&&y(p,t)?1:u?P(u,e)-P(u,t):0:4&n?-1:1)}:function(e,t){if(e===t)return l=!0,0;var n,r=0,i=e.parentNode,o=t.parentNode,a=[e],s=[t];if(!i||!o)return e==C?-1:t==C?1:i?-1:o?1:u?P(u,e)-P(u,t):0;if(i===o)return pe(e,t);n=e;while(n=n.parentNode)a.unshift(n);n=t;while(n=n.parentNode)s.unshift(n);while(a[r]===s[r])r++;return r?pe(a[r],s[r]):a[r]==p?-1:s[r]==p?1:0}),C},se.matches=function(e,t){return se(e,null,null,t)},se.matchesSelector=function(e,t){if(T(e),d.matchesSelector&&E&&!N[t+" "]&&(!s||!s.test(t))&&(!v||!v.test(t)))try{var n=c.call(e,t);if(n||d.disconnectedMatch||e.document&&11!==e.document.nodeType)return n}catch(e){N(t,!0)}return 0":{dir:"parentNode",first:!0}," ":{dir:"parentNode"},"+":{dir:"previousSibling",first:!0},"~":{dir:"previousSibling"}},preFilter:{ATTR:function(e){return e[1]=e[1].replace(te,ne),e[3]=(e[3]||e[4]||e[5]||"").replace(te,ne),"~="===e[2]&&(e[3]=" "+e[3]+" "),e.slice(0,4)},CHILD:function(e){return e[1]=e[1].toLowerCase(),"nth"===e[1].slice(0,3)?(e[3]||se.error(e[0]),e[4]=+(e[4]?e[5]+(e[6]||1):2*("even"===e[3]||"odd"===e[3])),e[5]=+(e[7]+e[8]||"odd"===e[3])):e[3]&&se.error(e[0]),e},PSEUDO:function(e){var t,n=!e[6]&&e[2];return G.CHILD.test(e[0])?null:(e[3]?e[2]=e[4]||e[5]||"":n&&X.test(n)&&(t=h(n,!0))&&(t=n.indexOf(")",n.length-t)-n.length)&&(e[0]=e[0].slice(0,t),e[2]=n.slice(0,t)),e.slice(0,3))}},filter:{TAG:function(e){var t=e.replace(te,ne).toLowerCase();return"*"===e?function(){return!0}:function(e){return e.nodeName&&e.nodeName.toLowerCase()===t}},CLASS:function(e){var t=m[e+" "];return t||(t=new RegExp("(^|"+M+")"+e+"("+M+"|$)"))&&m(e,function(e){return t.test("string"==typeof e.className&&e.className||"undefined"!=typeof e.getAttribute&&e.getAttribute("class")||"")})},ATTR:function(n,r,i){return function(e){var t=se.attr(e,n);return null==t?"!="===r:!r||(t+="","="===r?t===i:"!="===r?t!==i:"^="===r?i&&0===t.indexOf(i):"*="===r?i&&-1:\x20\t\r\n\f]*)[\x20\t\r\n\f]*\/?>(?:<\/\1>|)$/i;function D(e,n,r){return m(n)?S.grep(e,function(e,t){return!!n.call(e,t,e)!==r}):n.nodeType?S.grep(e,function(e){return e===n!==r}):"string"!=typeof n?S.grep(e,function(e){return-1)[^>]*|#([\w-]+))$/;(S.fn.init=function(e,t,n){var r,i;if(!e)return this;if(n=n||j,"string"==typeof e){if(!(r="<"===e[0]&&">"===e[e.length-1]&&3<=e.length?[null,e,null]:q.exec(e))||!r[1]&&t)return!t||t.jquery?(t||n).find(e):this.constructor(t).find(e);if(r[1]){if(t=t instanceof S?t[0]:t,S.merge(this,S.parseHTML(r[1],t&&t.nodeType?t.ownerDocument||t:E,!0)),N.test(r[1])&&S.isPlainObject(t))for(r in t)m(this[r])?this[r](t[r]):this.attr(r,t[r]);return this}return(i=E.getElementById(r[2]))&&(this[0]=i,this.length=1),this}return e.nodeType?(this[0]=e,this.length=1,this):m(e)?void 0!==n.ready?n.ready(e):e(S):S.makeArray(e,this)}).prototype=S.fn,j=S(E);var L=/^(?:parents|prev(?:Until|All))/,H={children:!0,contents:!0,next:!0,prev:!0};function O(e,t){while((e=e[t])&&1!==e.nodeType);return e}S.fn.extend({has:function(e){var t=S(e,this),n=t.length;return this.filter(function(){for(var e=0;e\x20\t\r\n\f]*)/i,he=/^$|^module$|\/(?:java|ecma)script/i;ce=E.createDocumentFragment().appendChild(E.createElement("div")),(fe=E.createElement("input")).setAttribute("type","radio"),fe.setAttribute("checked","checked"),fe.setAttribute("name","t"),ce.appendChild(fe),y.checkClone=ce.cloneNode(!0).cloneNode(!0).lastChild.checked,ce.innerHTML="",y.noCloneChecked=!!ce.cloneNode(!0).lastChild.defaultValue,ce.innerHTML="",y.option=!!ce.lastChild;var ge={thead:[1,"","
    "],col:[2,"","
    "],tr:[2,"","
    "],td:[3,"","
    "],_default:[0,"",""]};function ve(e,t){var n;return n="undefined"!=typeof e.getElementsByTagName?e.getElementsByTagName(t||"*"):"undefined"!=typeof e.querySelectorAll?e.querySelectorAll(t||"*"):[],void 0===t||t&&A(e,t)?S.merge([e],n):n}function ye(e,t){for(var n=0,r=e.length;n",""]);var me=/<|&#?\w+;/;function xe(e,t,n,r,i){for(var o,a,s,u,l,c,f=t.createDocumentFragment(),p=[],d=0,h=e.length;d\s*$/g;function qe(e,t){return A(e,"table")&&A(11!==t.nodeType?t:t.firstChild,"tr")&&S(e).children("tbody")[0]||e}function Le(e){return e.type=(null!==e.getAttribute("type"))+"/"+e.type,e}function He(e){return"true/"===(e.type||"").slice(0,5)?e.type=e.type.slice(5):e.removeAttribute("type"),e}function Oe(e,t){var n,r,i,o,a,s;if(1===t.nodeType){if(Y.hasData(e)&&(s=Y.get(e).events))for(i in Y.remove(t,"handle events"),s)for(n=0,r=s[i].length;n").attr(n.scriptAttrs||{}).prop({charset:n.scriptCharset,src:n.url}).on("load error",i=function(e){r.remove(),i=null,e&&t("error"===e.type?404:200,e.type)}),E.head.appendChild(r[0])},abort:function(){i&&i()}}});var Ut,Xt=[],Vt=/(=)\?(?=&|$)|\?\?/;S.ajaxSetup({jsonp:"callback",jsonpCallback:function(){var e=Xt.pop()||S.expando+"_"+Ct.guid++;return this[e]=!0,e}}),S.ajaxPrefilter("json jsonp",function(e,t,n){var r,i,o,a=!1!==e.jsonp&&(Vt.test(e.url)?"url":"string"==typeof e.data&&0===(e.contentType||"").indexOf("application/x-www-form-urlencoded")&&Vt.test(e.data)&&"data");if(a||"jsonp"===e.dataTypes[0])return r=e.jsonpCallback=m(e.jsonpCallback)?e.jsonpCallback():e.jsonpCallback,a?e[a]=e[a].replace(Vt,"$1"+r):!1!==e.jsonp&&(e.url+=(Et.test(e.url)?"&":"?")+e.jsonp+"="+r),e.converters["script json"]=function(){return o||S.error(r+" was not called"),o[0]},e.dataTypes[0]="json",i=C[r],C[r]=function(){o=arguments},n.always(function(){void 0===i?S(C).removeProp(r):C[r]=i,e[r]&&(e.jsonpCallback=t.jsonpCallback,Xt.push(r)),o&&m(i)&&i(o[0]),o=i=void 0}),"script"}),y.createHTMLDocument=((Ut=E.implementation.createHTMLDocument("").body).innerHTML="
    ",2===Ut.childNodes.length),S.parseHTML=function(e,t,n){return"string"!=typeof e?[]:("boolean"==typeof t&&(n=t,t=!1),t||(y.createHTMLDocument?((r=(t=E.implementation.createHTMLDocument("")).createElement("base")).href=E.location.href,t.head.appendChild(r)):t=E),o=!n&&[],(i=N.exec(e))?[t.createElement(i[1])]:(i=xe([e],t,o),o&&o.length&&S(o).remove(),S.merge([],i.childNodes)));var r,i,o},S.fn.load=function(e,t,n){var r,i,o,a=this,s=e.indexOf(" ");return-1").append(S.parseHTML(e)).find(r):e)}).always(n&&function(e,t){a.each(function(){n.apply(this,o||[e.responseText,t,e])})}),this},S.expr.pseudos.animated=function(t){return S.grep(S.timers,function(e){return t===e.elem}).length},S.offset={setOffset:function(e,t,n){var r,i,o,a,s,u,l=S.css(e,"position"),c=S(e),f={};"static"===l&&(e.style.position="relative"),s=c.offset(),o=S.css(e,"top"),u=S.css(e,"left"),("absolute"===l||"fixed"===l)&&-1<(o+u).indexOf("auto")?(a=(r=c.position()).top,i=r.left):(a=parseFloat(o)||0,i=parseFloat(u)||0),m(t)&&(t=t.call(e,n,S.extend({},s))),null!=t.top&&(f.top=t.top-s.top+a),null!=t.left&&(f.left=t.left-s.left+i),"using"in t?t.using.call(e,f):("number"==typeof f.top&&(f.top+="px"),"number"==typeof f.left&&(f.left+="px"),c.css(f))}},S.fn.extend({offset:function(t){if(arguments.length)return void 0===t?this:this.each(function(e){S.offset.setOffset(this,t,e)});var e,n,r=this[0];return r?r.getClientRects().length?(e=r.getBoundingClientRect(),n=r.ownerDocument.defaultView,{top:e.top+n.pageYOffset,left:e.left+n.pageXOffset}):{top:0,left:0}:void 0},position:function(){if(this[0]){var e,t,n,r=this[0],i={top:0,left:0};if("fixed"===S.css(r,"position"))t=r.getBoundingClientRect();else{t=this.offset(),n=r.ownerDocument,e=r.offsetParent||n.documentElement;while(e&&(e===n.body||e===n.documentElement)&&"static"===S.css(e,"position"))e=e.parentNode;e&&e!==r&&1===e.nodeType&&((i=S(e).offset()).top+=S.css(e,"borderTopWidth",!0),i.left+=S.css(e,"borderLeftWidth",!0))}return{top:t.top-i.top-S.css(r,"marginTop",!0),left:t.left-i.left-S.css(r,"marginLeft",!0)}}},offsetParent:function(){return this.map(function(){var e=this.offsetParent;while(e&&"static"===S.css(e,"position"))e=e.offsetParent;return e||re})}}),S.each({scrollLeft:"pageXOffset",scrollTop:"pageYOffset"},function(t,i){var o="pageYOffset"===i;S.fn[t]=function(e){return $(this,function(e,t,n){var r;if(x(e)?r=e:9===e.nodeType&&(r=e.defaultView),void 0===n)return r?r[i]:e[t];r?r.scrollTo(o?r.pageXOffset:n,o?n:r.pageYOffset):e[t]=n},t,e,arguments.length)}}),S.each(["top","left"],function(e,n){S.cssHooks[n]=$e(y.pixelPosition,function(e,t){if(t)return t=Be(e,n),Me.test(t)?S(e).position()[n]+"px":t})}),S.each({Height:"height",Width:"width"},function(a,s){S.each({padding:"inner"+a,content:s,"":"outer"+a},function(r,o){S.fn[o]=function(e,t){var n=arguments.length&&(r||"boolean"!=typeof e),i=r||(!0===e||!0===t?"margin":"border");return $(this,function(e,t,n){var r;return x(e)?0===o.indexOf("outer")?e["inner"+a]:e.document.documentElement["client"+a]:9===e.nodeType?(r=e.documentElement,Math.max(e.body["scroll"+a],r["scroll"+a],e.body["offset"+a],r["offset"+a],r["client"+a])):void 0===n?S.css(e,t,i):S.style(e,t,n,i)},s,n?e:void 0,n)}})}),S.each(["ajaxStart","ajaxStop","ajaxComplete","ajaxError","ajaxSuccess","ajaxSend"],function(e,t){S.fn[t]=function(e){return this.on(t,e)}}),S.fn.extend({bind:function(e,t,n){return this.on(e,null,t,n)},unbind:function(e,t){return this.off(e,null,t)},delegate:function(e,t,n,r){return this.on(t,e,n,r)},undelegate:function(e,t,n){return 1===arguments.length?this.off(e,"**"):this.off(t,e||"**",n)},hover:function(e,t){return this.mouseenter(e).mouseleave(t||e)}}),S.each("blur focus focusin focusout resize scroll click dblclick mousedown mouseup mousemove mouseover mouseout mouseenter mouseleave change select submit keydown keypress keyup contextmenu".split(" "),function(e,n){S.fn[n]=function(e,t){return 0>2,f=0;f>6),d.push(128|63&g)):g<55296?(d.push(224|g>>12),d.push(128|g>>6&63),d.push(128|63&g)):(g=(1023&g)<<10,g|=1023&a.charCodeAt(++b),g+=65536,d.push(240|g>>18),d.push(128|g>>12&63),d.push(128|g>>6&63),d.push(128|63&g))}return m(3,d.length),i(d);default:var j;if(Array.isArray(a))for(j=a.length,m(4,j),b=0;b>5!==a)throw"Invalid indefinite length element";return c}function s(a,b){for(var c=0;c>10),a.push(56320|1023&d))}}function t(){var a,e,f=l(),g=f>>5,m=31&f;if(7===g)switch(m){case 25:return i();case 26:return j();case 27:return k()}if(e=q(m),e<0&&(g<2||6=0;)o+=e,n.push(h(e));var u=new Uint8Array(o),v=0;for(a=0;a=0;)s(w,e);else s(w,e);return String.fromCharCode.apply(null,w);case 4:var x;if(e<0)for(x=[];!p();)x.push(t());else for(x=new Array(e),a=0;a0&&f._listeners.length>this._maxListeners&&(f._listeners.warned=!0,g.call(this,f._listeners.length,h))):f._listeners=b,!0;h=a.shift()}return!0}var k=Array.isArray?Array.isArray:function(a){return"[object Array]"===Object.prototype.toString.call(a)},l=10;h.EventEmitter2=h,h.prototype.delimiter=".",h.prototype.setMaxListeners=function(a){a!==d&&(this._maxListeners=a,this._conf||(this._conf={}),this._conf.maxListeners=a)},h.prototype.event="",h.prototype.once=function(a,b){return this._once(a,b,!1)},h.prototype.prependOnceListener=function(a,b){return this._once(a,b,!0)},h.prototype._once=function(a,b,c){return this._many(a,1,b,c),this},h.prototype.many=function(a,b,c){return this._many(a,b,c,!1)},h.prototype.prependMany=function(a,b,c){return this._many(a,b,c,!0)},h.prototype._many=function(a,b,c,d){function e(){return 0===--b&&f.off(a,e),c.apply(this,arguments)}var f=this;if("function"!=typeof c)throw new Error("many only accepts instances of Function");return e._origin=c,this._on(a,e,d),f},h.prototype.emit=function(){this._events||e.call(this);var a=arguments[0];if("newListener"===a&&!this.newListener&&!this._events.newListener)return!1;var b,c,d,f,g,h=arguments.length;if(this._all&&this._all.length){if(g=this._all.slice(),h>3)for(b=new Array(h),f=0;f3)for(b=new Array(h-1),f=1;f3)for(b=new Array(j),f=1;f3)for(b=new Array(j-1),f=1;f0&&this._events[a].length>this._maxListeners&&(this._events[a].warned=!0,g.call(this,this._events[a].length,a))):this._events[a]=b,this)},h.prototype.off=function(a,b){function c(a){if(a!==d){var b=Object.keys(a);for(var e in b){var f=b[e],g=a[f];g instanceof Function||"object"!=typeof g||null===g||(Object.keys(g).length>0&&c(a[f]),0===Object.keys(g).length&&delete a[f])}}}if("function"!=typeof b)throw new Error("removeListener only takes instances of Function");var e,f=[];if(this.wildcard){var g="string"==typeof a?a.split(this.delimiter):a.slice();f=i.call(this,null,g,this.listenerTree,0)}else{if(!this._events[a])return this;e=this._events[a],f.push({_listeners:e})}for(var h=0;h0){for(b=this._all,c=0,d=b.length;c1)for(var c=1;cb.secs)&&(a.secs0&&(this.parent=b[0].getAttribute("link"));var c=a.xml.getElementsByTagName("child");c.length>0&&(this.child=c[0].getAttribute("link"));var d=a.xml.getElementsByTagName("limit");d.length>0&&(this.minval=parseFloat(d[0].getAttribute("lower")),this.maxval=parseFloat(d[0].getAttribute("upper")));var h=a.xml.getElementsByTagName("origin");if(0===h.length)this.origin=new e;else{var i=h[0].getAttribute("xyz"),j=new f;i&&(i=i.split(" "),j=new f({x:parseFloat(i[0]),y:parseFloat(i[1]),z:parseFloat(i[2])}));var k=h[0].getAttribute("rpy"),l=new g;if(k){k=k.split(" ");var m=parseFloat(k[0]),n=parseFloat(k[1]),o=parseFloat(k[2]),p=m/2,q=n/2,r=o/2,s=Math.sin(p)*Math.cos(q)*Math.cos(r)-Math.cos(p)*Math.sin(q)*Math.sin(r),t=Math.cos(p)*Math.sin(q)*Math.cos(r)+Math.sin(p)*Math.cos(q)*Math.sin(r),u=Math.cos(p)*Math.cos(q)*Math.sin(r)-Math.sin(p)*Math.sin(q)*Math.cos(r),v=Math.cos(p)*Math.cos(q)*Math.cos(r)+Math.sin(p)*Math.sin(q)*Math.sin(r);l=new g({x:s,y:t,z:u,w:v}),l.normalize()}this.origin=new e({position:j,orientation:l})}}var e=a("../math/Pose"),f=a("../math/Vector3"),g=a("../math/Quaternion");b.exports=d},{"../math/Pose":21,"../math/Quaternion":22,"../math/Vector3":24}],33:[function(a,b,c){function d(a){this.name=a.xml.getAttribute("name"),this.visuals=[];for(var b=a.xml.getElementsByTagName("visual"),c=0;c0&&(this.textureFilename=b[0].getAttribute("filename"));var c=a.xml.getElementsByTagName("color");c.length>0&&(this.color=new e({xml:c[0]}))}var e=a("./UrdfColor");d.prototype.isLink=function(){return null===this.color&&null===this.textureFilename};var f=a("object-assign");d.prototype.assign=function(a){return f(this,a)},b.exports=d},{"./UrdfColor":30,"object-assign":3}],35:[function(a,b,c){function d(a){this.scale=null,this.type=f.URDF_MESH,this.filename=a.xml.getAttribute("filename");var b=a.xml.getAttribute("scale");if(b){var c=b.split(" ");this.scale=new e({x:parseFloat(c[0]),y:parseFloat(c[1]),z:parseFloat(c[2])})}}var e=a("../math/Vector3"),f=a("./UrdfTypes");b.exports=d},{"../math/Vector3":24,"./UrdfTypes":38}],36:[function(a,b,c){function d(a){a=a||{};var b=a.xml,c=a.string;if(this.materials={},this.links={},this.joints={},c){var d=new h;b=d.parseFromString(c,"text/xml")}var i=b.documentElement;this.name=i.getAttribute("name");for(var j=i.childNodes,k=0;k0){for(var A=z[0],B=null,C=0;C0&&(this.material=new j({xml:F[0]}))}var e=a("../math/Pose"),f=a("../math/Vector3"),g=a("../math/Quaternion"),h=a("./UrdfCylinder"),i=a("./UrdfBox"),j=a("./UrdfMaterial"),k=a("./UrdfMesh"),l=a("./UrdfSphere");b.exports=d},{"../math/Pose":21,"../math/Quaternion":22,"../math/Vector3":24,"./UrdfBox":29,"./UrdfCylinder":31,"./UrdfMaterial":34,"./UrdfMesh":35,"./UrdfSphere":37}],40:[function(a,b,c){b.exports=a("object-assign")({UrdfBox:a("./UrdfBox"),UrdfColor:a("./UrdfColor"),UrdfCylinder:a("./UrdfCylinder"),UrdfLink:a("./UrdfLink"),UrdfMaterial:a("./UrdfMaterial"),UrdfMesh:a("./UrdfMesh"),UrdfModel:a("./UrdfModel"),UrdfSphere:a("./UrdfSphere"),UrdfVisual:a("./UrdfVisual")},a("./UrdfTypes"))},{"./UrdfBox":29,"./UrdfColor":30,"./UrdfCylinder":31,"./UrdfLink":33,"./UrdfMaterial":34,"./UrdfMesh":35,"./UrdfModel":36,"./UrdfSphere":37,"./UrdfTypes":38,"./UrdfVisual":39,"object-assign":3}],41:[function(a,b,c){"use strict";function d(){j||(j=!0,console.warn("CBOR 64-bit integer array values may lose precision. No further warnings."))}function e(a){d();for(var b=a.byteLength,c=a.byteOffset,e=b/8,f=a.buffer.slice(c,c+b),g=new Uint32Array(f),h=new Array(e),j=0;j + + + + + +css + +.modal { + padding: 2rem; + border: 1px solid #eee; + width: max-content; + position: fixed; + right: 0; + bottom: 0; + max-width: 100%; +} + +.button-close-modal { + display: block; + font-size: 2rem; + font-weight: bold; + margin-left: auto; +} + +js + +document.addEventListener( + "click", + function (event) { + // If user either clicks X button OR clicks outside the modal window, then close modal by calling closeModal() + if ( + event.target.matches(".button-close-modal") || + !event.target.closest(".modal") + ) { + closeModal(); + } + }, + false +); + +function closeModal() { + document.querySelector(".modal").style.display = "none"; +} + diff --git a/mobile_manipulator/ifarlab_web/package.json b/mobile_manipulator/ifarlab_web/package.json new file mode 100644 index 0000000..361f859 --- /dev/null +++ b/mobile_manipulator/ifarlab_web/package.json @@ -0,0 +1,10 @@ +{ + "name": "rokos-chasis-inspection", + "version": "1.0.0", + "private": true, + "dependencies": { + "parcel-bundler": "^1.6.1" + }, + "scripts": {}, + "devDependencies": {} +} \ No newline at end of file diff --git a/mobile_manipulator/mobile_manipulator_action/CMakeLists.txt b/mobile_manipulator/mobile_manipulator_action/CMakeLists.txt new file mode 100644 index 0000000..ac3b7ff --- /dev/null +++ b/mobile_manipulator/mobile_manipulator_action/CMakeLists.txt @@ -0,0 +1,238 @@ +cmake_minimum_required(VERSION 3.0.2) +project(mobile_manipulator_action) + +## Compile as C++11, supported in ROS Kinetic and newer +# add_compile_options(-std=c++11) + +## Find catkin macros and libraries +## if COMPONENTS list like find_package(catkin REQUIRED COMPONENTS xyz) +## is used, also find other catkin packages +find_package(catkin REQUIRED COMPONENTS + actionlib + actionlib_msgs + message_generation + roscpp + rospy + std_msgs + geometry_msgs + sensor_msgs +) + +## System dependencies are found with CMake's conventions +# find_package(Boost REQUIRED COMPONENTS system) + + +## Uncomment this if the package has a setup.py. This macro ensures +## modules and global scripts declared therein get installed +## See http://ros.org/doc/api/catkin/html/user_guide/setup_dot_py.html +# catkin_python_setup() + +################################################ +## Declare ROS messages, services and actions ## +################################################ + +## To declare and build messages, services or actions from within this +## package, follow these steps: +## * Let MSG_DEP_SET be the set of packages whose message types you use in +## your messages/services/actions (e.g. std_msgs, actionlib_msgs, ...). +## * In the file package.xml: +## * add a build_depend tag for "message_generation" +## * add a build_depend and a exec_depend tag for each package in MSG_DEP_SET +## * If MSG_DEP_SET isn't empty the following dependency has been pulled in +## but can be declared for certainty nonetheless: +## * add a exec_depend tag for "message_runtime" +## * In this file (CMakeLists.txt): +## * add "message_generation" and every package in MSG_DEP_SET to +## find_package(catkin REQUIRED COMPONENTS ...) +## * add "message_runtime" and every package in MSG_DEP_SET to +## catkin_package(CATKIN_DEPENDS ...) +## * uncomment the add_*_files sections below as needed +## and list every .msg/.srv/.action file to be processed +## * uncomment the generate_messages entry below +## * add every package in MSG_DEP_SET to generate_messages(DEPENDENCIES ...) + +## Generate messages in the 'msg' folder +# add_message_files( +# FILES +# Message1.msg +# Message2.msg +# ) + +## Generate services in the 'srv' folder + add_service_files( + FILES + MobilePlatform.srv + VelocityService.srv + AccelerationService.srv + ) + +## Generate actions in the 'action' folder +ADD_ACTION_FILES( + DIRECTORY action + FILES MobilePlatform.action +) + +## Generate added messages and services with any dependencies listed here +generate_messages( + DEPENDENCIES + actionlib_msgs + std_msgs + geometry_msgs + sensor_msgs + ) + +################################################ +## Declare ROS dynamic reconfigure parameters ## +################################################ + +## To declare and build dynamic reconfigure parameters within this +## package, follow these steps: +## * In the file package.xml: +## * add a build_depend and a exec_depend tag for "dynamic_reconfigure" +## * In this file (CMakeLists.txt): +## * add "dynamic_reconfigure" to +## find_package(catkin REQUIRED COMPONENTS ...) +## * uncomment the "generate_dynamic_reconfigure_options" section below +## and list every .cfg file to be processed + +## Generate dynamic reconfigure parameters in the 'cfg' folder +# generate_dynamic_reconfigure_options( +# cfg/DynReconf1.cfg +# cfg/DynReconf2.cfg +# ) + +################################### +## catkin specific configuration ## +################################### +## The catkin_package macro generates cmake config files for your package +## Declare things to be passed to dependent projects +## INCLUDE_DIRS: uncomment this if your package contains header files +## LIBRARIES: libraries you create in this project that dependent projects also need +## CATKIN_DEPENDS: catkin_packages dependent projects also need +## DEPENDS: system dependencies of this project that dependent projects also need +catkin_package( + INCLUDE_DIRS include + LIBRARIES mobile_manipulator_action + CATKIN_DEPENDS actionlib actionlib_msgs message_generation roscpp rospy std_msgs + DEPENDS +) + +########### +## Build ## +########### + +## Specify additional locations of header files +## Your package locations should be listed before other locations +include_directories( +# include + ${catkin_INCLUDE_DIRS} +) + +## Declare a C++ library +# add_library(${PROJECT_NAME} +# src/${PROJECT_NAME}/mobile_manipulator_action.cpp +# ) + +## Add cmake target dependencies of the library +## as an example, code may need to be generated before libraries +## either from message generation or dynamic reconfigure +# add_dependencies(${PROJECT_NAME} ${${PROJECT_NAME}_EXPORTED_TARGETS} ${catkin_EXPORTED_TARGETS}) + +## Declare a C++ executable +## With catkin_make all packages are built within a single CMake context +## The recommended prefix ensures that target names across packages don't collide +# add_executable(${PROJECT_NAME}_node src/mobile_manipulator_action_node.cpp) +add_executable(mp_server src/action_server.cpp) +add_executable(mp_server2 src/action_server2.cpp) +add_executable(mp_client src/action_client.cpp) +## Rename C++ executable without prefix +## The above recommended prefix causes long target names, the following renames the +## target back to the shorter version for ease of user use +## e.g. "rosrun someones_pkg node" instead of "rosrun someones_pkg someones_pkg_node" +# set_target_properties(${PROJECT_NAME}_node PROPERTIES OUTPUT_NAME node PREFIX "") + +## Add cmake target dependencies of the executable +## same as for the library above +# add_dependencies(${PROJECT_NAME}_node ${${PROJECT_NAME}_EXPORTED_TARGETS} ${catkin_EXPORTED_TARGETS}) +add_dependencies( + mp_server + ${mobile_manipulator_action_EXPORTED_TARGETS} +) +add_dependencies( + mp_server2 + ${mobile_manipulator_action_EXPORTED_TARGETS} +) +add_dependencies( + mp_client + ${mobile_manipulator_action_EXPORTED_TARGETS} +) +## Specify libraries to link a library or executable target against +# target_link_libraries(${PROJECT_NAME}_node +# ${catkin_LIBRARIES} +# ) +target_link_libraries( + mp_server + ${catkin_LIBRARIES} +) +target_link_libraries( + mp_server2 + ${catkin_LIBRARIES} +) +target_link_libraries( + mp_client + ${catkin_LIBRARIES} +) +############# +## Install ## +############# + +# all install targets should use catkin DESTINATION variables +# See http://ros.org/doc/api/catkin/html/adv_user_guide/variables.html + +## Mark executable scripts (Python etc.) for installation +## in contrast to setup.py, you can choose the destination +# catkin_install_python(PROGRAMS +# scripts/my_python_script +# DESTINATION ${CATKIN_PACKAGE_BIN_DESTINATION} +# ) + +## Mark executables for installation +## See http://docs.ros.org/melodic/api/catkin/html/howto/format1/building_executables.html +# install(TARGETS ${PROJECT_NAME}_node +# RUNTIME DESTINATION ${CATKIN_PACKAGE_BIN_DESTINATION} +# ) + +## Mark libraries for installation +## See http://docs.ros.org/melodic/api/catkin/html/howto/format1/building_libraries.html +# install(TARGETS ${PROJECT_NAME} +# ARCHIVE DESTINATION ${CATKIN_PACKAGE_LIB_DESTINATION} +# LIBRARY DESTINATION ${CATKIN_PACKAGE_LIB_DESTINATION} +# RUNTIME DESTINATION ${CATKIN_GLOBAL_BIN_DESTINATION} +# ) + +## Mark cpp header files for installation +# install(DIRECTORY include/${PROJECT_NAME}/ +# DESTINATION ${CATKIN_PACKAGE_INCLUDE_DESTINATION} +# FILES_MATCHING PATTERN "*.h" +# PATTERN ".svn" EXCLUDE +# ) + +## Mark other files for installation (e.g. launch and bag files, etc.) +# install(FILES +# # myfile1 +# # myfile2 +# DESTINATION ${CATKIN_PACKAGE_SHARE_DESTINATION} +# ) + +############# +## Testing ## +############# + +## Add gtest based cpp test target and link libraries +# catkin_add_gtest(${PROJECT_NAME}-test test/test_mobile_manipulator_action.cpp) +# if(TARGET ${PROJECT_NAME}-test) +# target_link_libraries(${PROJECT_NAME}-test ${PROJECT_NAME}) +# endif() + +## Add folders to be run by python nosetests +# catkin_add_nosetests(test) diff --git a/mobile_manipulator/mobile_manipulator_action/action/MobilePlatform.action b/mobile_manipulator/mobile_manipulator_action/action/MobilePlatform.action new file mode 100644 index 0000000..895e1f6 --- /dev/null +++ b/mobile_manipulator/mobile_manipulator_action/action/MobilePlatform.action @@ -0,0 +1,11 @@ +#goal definition +float32[] goal +float32[] manuel +int32 cancel + +--- +#result definition +float32 result +--- +#feedback +float32 status diff --git a/mobile_manipulator/mobile_manipulator_action/launch/start_service.launch b/mobile_manipulator/mobile_manipulator_action/launch/start_service.launch new file mode 100644 index 0000000..33b830c --- /dev/null +++ b/mobile_manipulator/mobile_manipulator_action/launch/start_service.launch @@ -0,0 +1,12 @@ + + + + + + + + + + + + diff --git a/mobile_manipulator/mobile_manipulator_action/package.xml b/mobile_manipulator/mobile_manipulator_action/package.xml new file mode 100644 index 0000000..4d780f4 --- /dev/null +++ b/mobile_manipulator/mobile_manipulator_action/package.xml @@ -0,0 +1,77 @@ + + + mobile_manipulator_action + 0.0.0 + The mobile_manipulator_action package + + + + + didem-focal + + + + + + TODO + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + catkin + actionlib + actionlib_msgs + message_generation + roscpp + rospy + std_msgs + actionlib + actionlib_msgs + roscpp + rospy + std_msgs + message_generation + message_runtime + actionlib + actionlib_msgs + roscpp + rospy + std_msgs + + + + + + + + diff --git a/mobile_manipulator/mobile_manipulator_action/scripts/acceleration_service.py b/mobile_manipulator/mobile_manipulator_action/scripts/acceleration_service.py new file mode 100755 index 0000000..822668a --- /dev/null +++ b/mobile_manipulator/mobile_manipulator_action/scripts/acceleration_service.py @@ -0,0 +1,105 @@ +#!/usr/bin/env python3 +# coding=utf-8 + +""" +Service provider +Publishes acceleration depending cmd_vel command + +@Author: Furkan Edizkan +@Task: #IFARLAB +""" + + +import rospy +import numpy as np +from geometry_msgs.msg import Twist +from mobile_manipulator_action.srv import AccelerationService, AccelerationServiceResponse, AccelerationServiceRequest +from nav_msgs.msg import Odometry +from std_msgs.msg import Int8 + +ODOM_POSITION_X = None +cancel_data = 0 + +def ServiceCallback(req): + global ODOM_POSITION_X, cancel_data + rate_param = 20.0 + rospy.loginfo("acceleration_service::Received request == %s, %s", str(req.pos_x), str(req.vel_config)) + resp = AccelerationServiceResponse() + resp.response = 'Failed to get acceleration' + rospy.Subscriber("/mp_action/cancel", Int8, cancel_callback) + pub = rospy.Publisher('cmd_vel', Twist, queue_size=10) + cmd_msg = Twist() + + pos_x, vel_config = req.pos_x, abs(req.vel_config) + + if vel_config > 0.25: + vel_config = 0.25 + elif vel_config < 0.0: + vel_config = 0.0 + + if pos_x > 2.08: + pos_x = 2.08 + elif pos_x < 0.0: + pos_x = 0.0 + + try: + vel = 0 + pose_status = False + + while not rospy.is_shutdown(): + rospy.Rate(rate_param).sleep() + diff = pos_x - ODOM_POSITION_X + acc_param = np.sign(diff) * (vel_config/rate_param) + if cancel_data: + cmd_msg.linear.x = 0 + pub.publish(cmd_msg) + resp.response = 'Aborted' + cancel_data = 0 + break + else: + if abs(diff) > abs(vel_config)/2: + vel += acc_param + move_forward = True + if abs(vel) > abs(vel_config): + vel = np.sign(diff) * vel_config + else: + if not move_forward: + vel = np.sign(diff) * 0.08 + else: + vel = diff + + if abs(diff) < 0.005: + vel = 0 + pose_status = True + + cmd_msg.linear.x = vel + + pub.publish(cmd_msg) + + if pose_status: + resp.response = 'Succeeded' + rospy.loginfo("Succeeded") + break + + except Exception as err: + rospy.loginfo("acceleration_service::Error == %f", err) + resp.response = 'Aborted' + + return resp + + +def OdomCallback(msg): + """Odometry callback""" + global ODOM_POSITION_X + ODOM_POSITION_X = msg.pose.pose.position.x + +def cancel_callback(msg): + global cancel_data + cancel_data = msg.data + +if __name__ == '__main__': + rospy.init_node('acceleration_service') + rospy.Subscriber("/odom", Odometry, OdomCallback) + service = rospy.Service('acceleration_service', AccelerationService, ServiceCallback) + rospy.loginfo("acceleration_service service ready") + rospy.spin() \ No newline at end of file diff --git a/mobile_manipulator/mobile_manipulator_action/scripts/mobile_platform_service.py b/mobile_manipulator/mobile_manipulator_action/scripts/mobile_platform_service.py new file mode 100755 index 0000000..37b4675 --- /dev/null +++ b/mobile_manipulator/mobile_manipulator_action/scripts/mobile_platform_service.py @@ -0,0 +1,24 @@ +#!/usr/bin/env python3 +import rospy +from nav_msgs.msg import * +from mobile_manipulator_action.srv import MobilePlatform,MobilePlatformResponse +import rospy + +class MobilePlatfromService: + def __init__(self): + rospy.init_node('moile_platform_server') + s = rospy.Service('mobile_platform_service', MobilePlatform, self.server_response) + rospy.Subscriber("odom", Odometry, self.odom_callback) + print("Ready to add two ints.") + rospy.spin() + + def odom_callback(self, msg): + self.odom_vel_x = msg.twist.twist.linear.x + self.odom_x = msg.pose.pose.position.x + + def server_response(self, req): + status = "{\"velocity: \"" + str(self.odom_vel_x) + "," + "\"pose\": " + str(self.odom_x) + "}" + return MobilePlatformResponse(status) + +if __name__ == "__main__": + MobilePlatfromService() \ No newline at end of file diff --git a/mobile_manipulator/mobile_manipulator_action/scripts/velocity_service.py b/mobile_manipulator/mobile_manipulator_action/scripts/velocity_service.py new file mode 100755 index 0000000..8125094 --- /dev/null +++ b/mobile_manipulator/mobile_manipulator_action/scripts/velocity_service.py @@ -0,0 +1,36 @@ +#!/usr/bin/env python3 +# coding=utf-8 + +""" +Service provider +Publishes given cmd_vel command + +@Author: Furkan Edizkan +@Task: #IFARLAB +""" + +import rospy +from geometry_msgs.msg import Twist +from mobile_manipulator_action.srv import VelocityService, VelocityServiceResponse, VelocityServiceRequest + +pub = rospy.Publisher('cmd_vel', Twist, queue_size=10) +cmd_msg = Twist() + +def ServiceCallback(req): + vel = req.cmd_msg.linear.x + if vel > 0.25: + vel = 0.25 + cmd_msg.linear.x = vel + cmd_msg = req.cmd_msg + rospy.loginfo("velocity_service::Received request == \n%s", str(cmd_msg)) + pub.publish(cmd_msg) + + resp = VelocityServiceResponse() + return resp + + +if __name__ == '__main__': + rospy.init_node('velocity_service') + service = rospy.Service('velocity_service', VelocityService, ServiceCallback) + rospy.loginfo("velocity_service service ready") + rospy.spin() \ No newline at end of file diff --git a/mobile_manipulator/mobile_manipulator_action/src/.action_server2.cpp.swp b/mobile_manipulator/mobile_manipulator_action/src/.action_server2.cpp.swp new file mode 100644 index 0000000..63b6a84 Binary files /dev/null and b/mobile_manipulator/mobile_manipulator_action/src/.action_server2.cpp.swp differ diff --git a/mobile_manipulator/mobile_manipulator_action/src/action_client.cpp b/mobile_manipulator/mobile_manipulator_action/src/action_client.cpp new file mode 100755 index 0000000..817d3eb --- /dev/null +++ b/mobile_manipulator/mobile_manipulator_action/src/action_client.cpp @@ -0,0 +1,38 @@ +#include +#include +#include +#include + +int main (int argc, char **argv) +{ + ros::init(argc, argv, "test_fibonacci"); + + // create the action client + // true causes the client to spin its own thread + actionlib::SimpleActionClient ac("mobile_platform", true); + + ROS_INFO("Waiting for action server to start."); + // wait for the action server to start + ac.waitForServer(); //will wait for infinite time + + ROS_INFO("Action server started, sending goal."); + // send a goal to the action + mobile_manipulator_action::MobilePlatformGoal goal; + goal.goal = {0, 0.1}; + // goal.manuel = {0, 0.1}; + ac.sendGoal(goal); + + //wait for the action to return + bool finished_before_timeout = ac.waitForResult(ros::Duration(50000.0)); + + if (finished_before_timeout) + { + actionlib::SimpleClientGoalState state = ac.getState(); + ROS_INFO("Action finished: %s",state.toString().c_str()); + } + else + ROS_INFO("Action did not finish before the time out."); + + //exit + return 0; +} diff --git a/mobile_manipulator/mobile_manipulator_action/src/action_server.cpp b/mobile_manipulator/mobile_manipulator_action/src/action_server.cpp new file mode 100755 index 0000000..c46dae4 --- /dev/null +++ b/mobile_manipulator/mobile_manipulator_action/src/action_server.cpp @@ -0,0 +1,164 @@ +#include +#include +#include +#include +#include +#include +#include + + +double signnum_c(double x) { + if (x > 0.0) return 1.0; + if (x < 0.0) return -1.0; + return x; +} + +class MobilePlatformAction +{ +protected: + float odom_pos_x; + float odom_lin_x; + int cancel; + + ros::NodeHandle nh_; + actionlib::SimpleActionServer as_; +// NodeHandle instance must be created before this line. Otherwise strange error occurs. + std::string action_name_; + // create messages that are used to published feedback/result + mobile_manipulator_action::MobilePlatformFeedback feedback_; + mobile_manipulator_action::MobilePlatformResult result_; + ros::Publisher cmd_pub = nh_.advertise("cmd_vel", 1000); + geometry_msgs::Twist cmd_msg; + ros::Subscriber sub_ = nh_.subscribe("odom", 1000, &MobilePlatformAction::odomCallback, this); + ros::Subscriber sub_cancel_ = nh_.subscribe("mp_action/cancel", 1000, &MobilePlatformAction::actionCancelCallback, this); + +public: + + MobilePlatformAction(std::string name) : + as_(nh_, name, boost::bind(&MobilePlatformAction::executeCB, this, _1), false), + action_name_(name) + { + as_.start(); + } + + ~MobilePlatformAction(void) + { + } + + void executeCB(const mobile_manipulator_action::MobilePlatformGoalConstPtr &goal) + { + // helper variables + float rate_param = 20.0; + ros::Rate r(rate_param); + bool success = false; + float vel, acc_param; + float diff = 0; + bool pose_status = false; + bool move_forward = true; + success = false; + cancel = 0; + // publish info to the console for the user + ROS_INFO("Executing, creating fibonacci sequence of order"); + + // start executing the action + + if (goal->manuel.size() > 0){ + + float manuel_dir = goal->manuel[0]; + float manuel_vel = goal->manuel[1]; + cmd_msg.linear.x = manuel_dir * manuel_vel; + cmd_pub.publish(cmd_msg); + success = true; + feedback_.status = 1; + result_.result = 1; + } + + if (goal->goal.size()>0){ + float goal_vel = std::abs(goal->goal[0]); + float goal_pose = goal->goal[1]; + if (goal_vel > 0.25){ + goal_vel = 0; + } + while (!success){ + if (cancel == 1){ + cmd_msg.linear.x = 0; + cmd_pub.publish(cmd_msg); + feedback_.status = 0; + result_.result = 0; + success = true; + } + if (odom_pos_x) + { + std::cout<<"pose"< std::abs(goal_vel)){ + vel += acc_param; + move_forward = true; + if (std::abs(vel) > std::abs(goal_vel)){ + vel = signnum_c(diff) * goal_vel; + } + } + else{ + if (!move_forward){ + vel = signnum_c(diff) * 0.05; + } + else{ + vel = diff; + } + } + if (std::abs(diff) < 0.005){ + vel = 0; + pose_status = true; + success = true; + feedback_.status = 1; + result_.result = 1; + } + cmd_msg.linear.x = vel; + cmd_pub.publish(cmd_msg); + } + ros::spinOnce(); + + r.sleep(); + } + + } + + if(success) + { + ROS_INFO("%s: Succeeded", action_name_.c_str()); + // set the action state to succeeded + as_.setSucceeded(result_); + } + ros::spinOnce(); + + r.sleep(); + } + + void odomCallback(const nav_msgs::Odometry::ConstPtr& msg) + { + //std::cout<pose.pose.position.x<twist.twist.linear.x<pose.pose.position.x; + odom_lin_x = msg->twist.twist.linear.x; + + } + + void actionCancelCallback(const std_msgs::Int8::ConstPtr& msg) + { + cancel = msg->data; + } +}; + + +int main(int argc, char** argv) +{ + ros::init(argc, argv, "mobile_platform"); + + MobilePlatformAction mobile_platform("mobile_platform"); + ros::spin(); + + return 0; +} diff --git a/mobile_manipulator/mobile_manipulator_action/src/action_server2.cpp b/mobile_manipulator/mobile_manipulator_action/src/action_server2.cpp new file mode 100755 index 0000000..fe73500 --- /dev/null +++ b/mobile_manipulator/mobile_manipulator_action/src/action_server2.cpp @@ -0,0 +1,178 @@ +#include +#include +#include +#include +#include +#include +#include + + +double signnum_c(double x){ + if (x > 0.0) + return 1.0; + if (x < 0.0) + return -1.0; + return x; +} + +class MobilePlatformAction +{ +protected: + float odom_pos_x; + float odom_lin_x; + int cancel; + + ros::NodeHandle nh_; + actionlib::SimpleActionServer as_; +// NodeHandle instance must be created before this line. Otherwise strange error occurs. + std::string action_name_; + // create messages that are used to published feedback/result + mobile_manipulator_action::MobilePlatformFeedback feedback_; + mobile_manipulator_action::MobilePlatformResult result_; + ros::Publisher cmd_pub = nh_.advertise("cmd_vel", 1000); + geometry_msgs::Twist cmd_msg; + ros::Subscriber sub_ = nh_.subscribe("odom", 1000, &MobilePlatformAction::odomCallback, this); + ros::Subscriber sub_cancel_ = nh_.subscribe("mp_action/cancel", 1000, &MobilePlatformAction::actionCancelCallback, this); + +public: + + MobilePlatformAction(std::string name) : + as_(nh_, name, boost::bind(&MobilePlatformAction::executeCB, this, _1), false), + action_name_(name) + { + as_.start(); + } + + ~MobilePlatformAction(void) + { + } + + void executeCB(const mobile_manipulator_action::MobilePlatformGoalConstPtr &goal) + { + // helper variables + float rate_param = 10.0; + ros::Rate r(10); + bool success = false; + float vel, acc_param; + float diff = 0; + bool pose_status = false; + bool move_forward = true; + success = false; + cancel = 0; + // publish info to the console for the user + ROS_INFO("Executing, creating fibonacci sequence of order"); + + // start executing the action + + if (goal->manuel.size() > 0){ + + float manuel_dir = goal->manuel[0]; + float manuel_vel = goal->manuel[1]; + cmd_msg.linear.x = manuel_dir * manuel_vel; + cmd_pub.publish(cmd_msg); + success = true; + feedback_.status = 1; + result_.result = 1; + } + + if (goal->goal.size()>0){ + float goal_vel = goal->goal[0]; + float goal_pose = goal->goal[1]; + + if (goal_vel > 0.25){ + goal_vel = 0.25; + } + else if (goal_vel < 0.0){ + goal_vel = 0.0; + } + + if (goal_pose > 2.08){ + goal_pose = 2.08; + } + else if (goal_pose < 0.0){ + goal_pose = 0.0; + } + + while (!success){ + if (cancel == 1){ + feedback_.status = 0; + result_.result = 0; + success = true; + } + if (odom_pos_x) + { + std::cout<<"pose"< std::abs(goal_vel)){ + vel += acc_param; + } + else if (std::abs(diff) <= std::abs(goal_vel)){ + vel = diff * 0.8; + } + + if (std::abs(vel) > std::abs(goal_vel)){ + vel = signnum_c(diff) * goal_vel; + } + + if (std::abs(vel) < std::abs(acc_param)){ + vel = 0; + } + + if (std::abs(diff) < (std::abs(goal_vel) * 0.2)){ + vel = 0; + pose_status = true; + success = true; + feedback_.status = 1; + result_.result = 1; + } + + cmd_msg.linear.x = vel; + cmd_pub.publish(cmd_msg); + } + ros::spinOnce(); + + r.sleep(); + } + + } + + if(success) + { + ROS_INFO("%s: Succeeded", action_name_.c_str()); + // set the action state to succeeded + as_.setSucceeded(result_); + } + ros::spinOnce(); + + r.sleep(); + } + + void odomCallback(const nav_msgs::Odometry::ConstPtr& msg) + { + //std::cout<pose.pose.position.x<twist.twist.linear.x<pose.pose.position.x; + odom_lin_x = msg->twist.twist.linear.x; + + } + + void actionCancelCallback(const std_msgs::Int8::ConstPtr& msg) + { + cancel = msg->data; + } +}; + + +int main(int argc, char** argv) +{ + ros::init(argc, argv, "mobile_platform"); + + MobilePlatformAction mobile_platform("mobile_platform"); + ros::spin(); + + return 0; +} diff --git a/mobile_manipulator/mobile_manipulator_action/srv/AccelerationService.srv b/mobile_manipulator/mobile_manipulator_action/srv/AccelerationService.srv new file mode 100644 index 0000000..40f47a0 --- /dev/null +++ b/mobile_manipulator/mobile_manipulator_action/srv/AccelerationService.srv @@ -0,0 +1,4 @@ +float64 pos_x +float64 vel_config +--- +string response \ No newline at end of file diff --git a/mobile_manipulator/mobile_manipulator_action/srv/MobilePlatform.srv b/mobile_manipulator/mobile_manipulator_action/srv/MobilePlatform.srv new file mode 100644 index 0000000..c2279af --- /dev/null +++ b/mobile_manipulator/mobile_manipulator_action/srv/MobilePlatform.srv @@ -0,0 +1,2 @@ +--- +string status diff --git a/mobile_manipulator/mobile_manipulator_action/srv/VelocityService.srv b/mobile_manipulator/mobile_manipulator_action/srv/VelocityService.srv new file mode 100644 index 0000000..97f73fc --- /dev/null +++ b/mobile_manipulator/mobile_manipulator_action/srv/VelocityService.srv @@ -0,0 +1,2 @@ +geometry_msgs/Twist cmd_msg +--- \ No newline at end of file diff --git a/mobile_manipulator/mobile_manipulator_config_v1/.setup_assistant b/mobile_manipulator/mobile_manipulator_config_v1/.setup_assistant new file mode 100644 index 0000000..4556528 --- /dev/null +++ b/mobile_manipulator/mobile_manipulator_config_v1/.setup_assistant @@ -0,0 +1,11 @@ +moveit_setup_assistant_config: + URDF: + package: mobile_manipulator_description + relative_path: urdf/mobile_manipulator.urdf.xacro + xacro_args: "" + SRDF: + relative_path: config/robot.srdf + CONFIG: + author_name: didem + author_email: didem@didem.com + generated_timestamp: 1671461756 \ No newline at end of file diff --git a/mobile_manipulator/mobile_manipulator_config_v1/CMakeLists.txt b/mobile_manipulator/mobile_manipulator_config_v1/CMakeLists.txt new file mode 100644 index 0000000..54a3f79 --- /dev/null +++ b/mobile_manipulator/mobile_manipulator_config_v1/CMakeLists.txt @@ -0,0 +1,10 @@ +cmake_minimum_required(VERSION 3.1.3) +project(mobile_manipulator_config_v1) + +find_package(catkin REQUIRED) + +catkin_package() + +install(DIRECTORY launch DESTINATION ${CATKIN_PACKAGE_SHARE_DESTINATION} + PATTERN "setup_assistant.launch" EXCLUDE) +install(DIRECTORY config DESTINATION ${CATKIN_PACKAGE_SHARE_DESTINATION}) diff --git a/mobile_manipulator/mobile_manipulator_config_v1/config/cartesian_limits.yaml b/mobile_manipulator/mobile_manipulator_config_v1/config/cartesian_limits.yaml new file mode 100644 index 0000000..7df72f6 --- /dev/null +++ b/mobile_manipulator/mobile_manipulator_config_v1/config/cartesian_limits.yaml @@ -0,0 +1,5 @@ +cartesian_limits: + max_trans_vel: 1 + max_trans_acc: 2.25 + max_trans_dec: -5 + max_rot_vel: 1.57 diff --git a/mobile_manipulator/mobile_manipulator_config_v1/config/chomp_planning.yaml b/mobile_manipulator/mobile_manipulator_config_v1/config/chomp_planning.yaml new file mode 100644 index 0000000..eb9c912 --- /dev/null +++ b/mobile_manipulator/mobile_manipulator_config_v1/config/chomp_planning.yaml @@ -0,0 +1,18 @@ +planning_time_limit: 10.0 +max_iterations: 200 +max_iterations_after_collision_free: 5 +smoothness_cost_weight: 0.1 +obstacle_cost_weight: 1.0 +learning_rate: 0.01 +smoothness_cost_velocity: 0.0 +smoothness_cost_acceleration: 1.0 +smoothness_cost_jerk: 0.0 +ridge_factor: 0.0 +use_pseudo_inverse: false +pseudo_inverse_ridge_factor: 1e-4 +joint_update_limit: 0.1 +collision_clearance: 0.2 +collision_threshold: 0.07 +use_stochastic_descent: true +enable_failure_recovery: false +max_recovery_attempts: 5 diff --git a/mobile_manipulator/mobile_manipulator_config_v1/config/fake_controllers.yaml b/mobile_manipulator/mobile_manipulator_config_v1/config/fake_controllers.yaml new file mode 100644 index 0000000..00ce021 --- /dev/null +++ b/mobile_manipulator/mobile_manipulator_config_v1/config/fake_controllers.yaml @@ -0,0 +1,13 @@ +controller_list: + - name: fake_manipulator_controller + type: $(arg fake_execution_type) + joints: + - joint1 + - joint2 + - joint3 + - joint4 + - joint5 + - joint6 +initial: # Define initial robot poses per group + - group: manipulator + pose: home \ No newline at end of file diff --git a/mobile_manipulator/mobile_manipulator_config_v1/config/gazebo_controllers.yaml b/mobile_manipulator/mobile_manipulator_config_v1/config/gazebo_controllers.yaml new file mode 100644 index 0000000..e4d2eb0 --- /dev/null +++ b/mobile_manipulator/mobile_manipulator_config_v1/config/gazebo_controllers.yaml @@ -0,0 +1,4 @@ +# Publish joint_states +joint_state_controller: + type: joint_state_controller/JointStateController + publish_rate: 50 diff --git a/mobile_manipulator/mobile_manipulator_config_v1/config/joint_limits.yaml b/mobile_manipulator/mobile_manipulator_config_v1/config/joint_limits.yaml new file mode 100644 index 0000000..9d01bfa --- /dev/null +++ b/mobile_manipulator/mobile_manipulator_config_v1/config/joint_limits.yaml @@ -0,0 +1,40 @@ +# joint_limits.yaml allows the dynamics properties specified in the URDF to be overwritten or augmented as needed + +# For beginners, we downscale velocity and acceleration limits. +# You can always specify higher scaling factors (<= 1.0) in your motion requests. # Increase the values below to 1.0 to always move at maximum speed. +default_velocity_scaling_factor: 0.1 +default_acceleration_scaling_factor: 0.1 + +# Specific joint properties can be changed with the keys [max_position, min_position, max_velocity, max_acceleration] +# Joint limits can be turned off with [has_velocity_limits, has_acceleration_limits] +joint_limits: + joint1: + has_velocity_limits: true + max_velocity: 5.235987755982989 + has_acceleration_limits: false + max_acceleration: 0 + joint2: + has_velocity_limits: true + max_velocity: 5.235987755982989 + has_acceleration_limits: false + max_acceleration: 0 + joint3: + has_velocity_limits: true + max_velocity: 5.235987755982989 + has_acceleration_limits: false + max_acceleration: 0 + joint4: + has_velocity_limits: true + max_velocity: 8.028514559173916 + has_acceleration_limits: false + max_acceleration: 0 + joint5: + has_velocity_limits: true + max_velocity: 8.028514559173916 + has_acceleration_limits: false + max_acceleration: 0 + joint6: + has_velocity_limits: true + max_velocity: 12.91543646475804 + has_acceleration_limits: false + max_acceleration: 0 \ No newline at end of file diff --git a/mobile_manipulator/mobile_manipulator_config_v1/config/kinematics.yaml b/mobile_manipulator/mobile_manipulator_config_v1/config/kinematics.yaml new file mode 100644 index 0000000..ad478ed --- /dev/null +++ b/mobile_manipulator/mobile_manipulator_config_v1/config/kinematics.yaml @@ -0,0 +1,4 @@ +manipulator: + kinematics_solver: kdl_kinematics_plugin/KDLKinematicsPlugin + kinematics_solver_search_resolution: 0.005 + kinematics_solver_timeout: 0.005 \ No newline at end of file diff --git a/mobile_manipulator/mobile_manipulator_config_v1/config/ompl_planning.yaml b/mobile_manipulator/mobile_manipulator_config_v1/config/ompl_planning.yaml new file mode 100644 index 0000000..1659ede --- /dev/null +++ b/mobile_manipulator/mobile_manipulator_config_v1/config/ompl_planning.yaml @@ -0,0 +1,158 @@ +planner_configs: + AnytimePathShortening: + type: geometric::AnytimePathShortening + shortcut: true # Attempt to shortcut all new solution paths + hybridize: true # Compute hybrid solution trajectories + max_hybrid_paths: 24 # Number of hybrid paths generated per iteration + num_planners: 4 # The number of default planners to use for planning + planners: "" # A comma-separated list of planner types (e.g., "PRM,EST,RRTConnect"Optionally, planner parameters can be passed to change the default:"PRM[max_nearest_neighbors=5],EST[goal_bias=.5],RRT[range=10. goal_bias=.1]" + SBL: + type: geometric::SBL + range: 0.0 # Max motion added to tree. ==> maxDistance_ default: 0.0, if 0.0, set on setup() + EST: + type: geometric::EST + range: 0.0 # Max motion added to tree. ==> maxDistance_ default: 0.0, if 0.0 setup() + goal_bias: 0.05 # When close to goal select goal, with this probability. default: 0.05 + LBKPIECE: + type: geometric::LBKPIECE + range: 0.0 # Max motion added to tree. ==> maxDistance_ default: 0.0, if 0.0, set on setup() + border_fraction: 0.9 # Fraction of time focused on boarder default: 0.9 + min_valid_path_fraction: 0.5 # Accept partially valid moves above fraction. default: 0.5 + BKPIECE: + type: geometric::BKPIECE + range: 0.0 # Max motion added to tree. ==> maxDistance_ default: 0.0, if 0.0, set on setup() + border_fraction: 0.9 # Fraction of time focused on boarder default: 0.9 + failed_expansion_score_factor: 0.5 # When extending motion fails, scale score by factor. default: 0.5 + min_valid_path_fraction: 0.5 # Accept partially valid moves above fraction. default: 0.5 + KPIECE: + type: geometric::KPIECE + range: 0.0 # Max motion added to tree. ==> maxDistance_ default: 0.0, if 0.0, set on setup() + goal_bias: 0.05 # When close to goal select goal, with this probability. default: 0.05 + border_fraction: 0.9 # Fraction of time focused on boarder default: 0.9 (0.0,1.] + failed_expansion_score_factor: 0.5 # When extending motion fails, scale score by factor. default: 0.5 + min_valid_path_fraction: 0.5 # Accept partially valid moves above fraction. default: 0.5 + RRT: + type: geometric::RRT + range: 0.0 # Max motion added to tree. ==> maxDistance_ default: 0.0, if 0.0, set on setup() + goal_bias: 0.05 # When close to goal select goal, with this probability? default: 0.05 + RRTConnect: + type: geometric::RRTConnect + range: 0.0 # Max motion added to tree. ==> maxDistance_ default: 0.0, if 0.0, set on setup() + RRTstar: + type: geometric::RRTstar + range: 0.0 # Max motion added to tree. ==> maxDistance_ default: 0.0, if 0.0, set on setup() + goal_bias: 0.05 # When close to goal select goal, with this probability? default: 0.05 + delay_collision_checking: 1 # Stop collision checking as soon as C-free parent found. default 1 + TRRT: + type: geometric::TRRT + range: 0.0 # Max motion added to tree. ==> maxDistance_ default: 0.0, if 0.0, set on setup() + goal_bias: 0.05 # When close to goal select goal, with this probability? default: 0.05 + max_states_failed: 10 # when to start increasing temp. default: 10 + temp_change_factor: 2.0 # how much to increase or decrease temp. default: 2.0 + min_temperature: 10e-10 # lower limit of temp change. default: 10e-10 + init_temperature: 10e-6 # initial temperature. default: 10e-6 + frountier_threshold: 0.0 # dist new state to nearest neighbor to disqualify as frontier. default: 0.0 set in setup() + frountierNodeRatio: 0.1 # 1/10, or 1 nonfrontier for every 10 frontier. default: 0.1 + k_constant: 0.0 # value used to normalize expresssion. default: 0.0 set in setup() + PRM: + type: geometric::PRM + max_nearest_neighbors: 10 # use k nearest neighbors. default: 10 + PRMstar: + type: geometric::PRMstar + FMT: + type: geometric::FMT + num_samples: 1000 # number of states that the planner should sample. default: 1000 + radius_multiplier: 1.1 # multiplier used for the nearest neighbors search radius. default: 1.1 + nearest_k: 1 # use Knearest strategy. default: 1 + cache_cc: 1 # use collision checking cache. default: 1 + heuristics: 0 # activate cost to go heuristics. default: 0 + extended_fmt: 1 # activate the extended FMT*: adding new samples if planner does not finish successfully. default: 1 + BFMT: + type: geometric::BFMT + num_samples: 1000 # number of states that the planner should sample. default: 1000 + radius_multiplier: 1.0 # multiplier used for the nearest neighbors search radius. default: 1.0 + nearest_k: 1 # use the Knearest strategy. default: 1 + balanced: 0 # exploration strategy: balanced true expands one tree every iteration. False will select the tree with lowest maximum cost to go. default: 1 + optimality: 1 # termination strategy: optimality true finishes when the best possible path is found. Otherwise, the algorithm will finish when the first feasible path is found. default: 1 + heuristics: 1 # activates cost to go heuristics. default: 1 + cache_cc: 1 # use the collision checking cache. default: 1 + extended_fmt: 1 # Activates the extended FMT*: adding new samples if planner does not finish successfully. default: 1 + PDST: + type: geometric::PDST + STRIDE: + type: geometric::STRIDE + range: 0.0 # Max motion added to tree. ==> maxDistance_ default: 0.0, if 0.0, set on setup() + goal_bias: 0.05 # When close to goal select goal, with this probability. default: 0.05 + use_projected_distance: 0 # whether nearest neighbors are computed based on distances in a projection of the state rather distances in the state space itself. default: 0 + degree: 16 # desired degree of a node in the Geometric Near-neightbor Access Tree (GNAT). default: 16 + max_degree: 18 # max degree of a node in the GNAT. default: 12 + min_degree: 12 # min degree of a node in the GNAT. default: 12 + max_pts_per_leaf: 6 # max points per leaf in the GNAT. default: 6 + estimated_dimension: 0.0 # estimated dimension of the free space. default: 0.0 + min_valid_path_fraction: 0.2 # Accept partially valid moves above fraction. default: 0.2 + BiTRRT: + type: geometric::BiTRRT + range: 0.0 # Max motion added to tree. ==> maxDistance_ default: 0.0, if 0.0, set on setup() + temp_change_factor: 0.1 # how much to increase or decrease temp. default: 0.1 + init_temperature: 100 # initial temperature. default: 100 + frountier_threshold: 0.0 # dist new state to nearest neighbor to disqualify as frontier. default: 0.0 set in setup() + frountier_node_ratio: 0.1 # 1/10, or 1 nonfrontier for every 10 frontier. default: 0.1 + cost_threshold: 1e300 # the cost threshold. Any motion cost that is not better will not be expanded. default: inf + LBTRRT: + type: geometric::LBTRRT + range: 0.0 # Max motion added to tree. ==> maxDistance_ default: 0.0, if 0.0, set on setup() + goal_bias: 0.05 # When close to goal select goal, with this probability. default: 0.05 + epsilon: 0.4 # optimality approximation factor. default: 0.4 + BiEST: + type: geometric::BiEST + range: 0.0 # Max motion added to tree. ==> maxDistance_ default: 0.0, if 0.0, set on setup() + ProjEST: + type: geometric::ProjEST + range: 0.0 # Max motion added to tree. ==> maxDistance_ default: 0.0, if 0.0, set on setup() + goal_bias: 0.05 # When close to goal select goal, with this probability. default: 0.05 + LazyPRM: + type: geometric::LazyPRM + range: 0.0 # Max motion added to tree. ==> maxDistance_ default: 0.0, if 0.0, set on setup() + LazyPRMstar: + type: geometric::LazyPRMstar + SPARS: + type: geometric::SPARS + stretch_factor: 3.0 # roadmap spanner stretch factor. multiplicative upper bound on path quality. It does not make sense to make this parameter more than 3. default: 3.0 + sparse_delta_fraction: 0.25 # delta fraction for connection distance. This value represents the visibility range of sparse samples. default: 0.25 + dense_delta_fraction: 0.001 # delta fraction for interface detection. default: 0.001 + max_failures: 1000 # maximum consecutive failure limit. default: 1000 + SPARStwo: + type: geometric::SPARStwo + stretch_factor: 3.0 # roadmap spanner stretch factor. multiplicative upper bound on path quality. It does not make sense to make this parameter more than 3. default: 3.0 + sparse_delta_fraction: 0.25 # delta fraction for connection distance. This value represents the visibility range of sparse samples. default: 0.25 + dense_delta_fraction: 0.001 # delta fraction for interface detection. default: 0.001 + max_failures: 5000 # maximum consecutive failure limit. default: 5000 +manipulator: + default_planner_config: RRTstar + planner_configs: + - AnytimePathShortening + - SBL + - EST + - LBKPIECE + - BKPIECE + - KPIECE + - RRT + - RRTConnect + - RRTstar + - TRRT + - PRM + - PRMstar + - FMT + - BFMT + - PDST + - STRIDE + - BiTRRT + - LBTRRT + - BiEST + - ProjEST + - LazyPRM + - LazyPRMstar + - SPARS + - SPARStwo + projection_evaluator: joints(joint1,joint2) + longest_valid_segment_fraction: 0.005 diff --git a/mobile_manipulator/mobile_manipulator_config_v1/config/robot.srdf b/mobile_manipulator/mobile_manipulator_config_v1/config/robot.srdf new file mode 100644 index 0000000..fdeb790 --- /dev/null +++ b/mobile_manipulator/mobile_manipulator_config_v1/config/robot.srdf @@ -0,0 +1,177 @@ + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + diff --git a/mobile_manipulator/mobile_manipulator_config_v1/config/ros_controllers.yaml b/mobile_manipulator/mobile_manipulator_config_v1/config/ros_controllers.yaml new file mode 100644 index 0000000..230bcbb --- /dev/null +++ b/mobile_manipulator/mobile_manipulator_config_v1/config/ros_controllers.yaml @@ -0,0 +1,40 @@ +manipulator_controller: + type: position_controllers/JointTrajectoryController + joints: + - joint1 + - joint2 + - joint3 + - joint4 + - joint5 + - joint6 + gains: + joint1: + p: 100 + d: 1 + i: 1 + i_clamp: 1 + joint2: + p: 100 + d: 1 + i: 1 + i_clamp: 1 + joint3: + p: 100 + d: 1 + i: 1 + i_clamp: 1 + joint4: + p: 100 + d: 1 + i: 1 + i_clamp: 1 + joint5: + p: 100 + d: 1 + i: 1 + i_clamp: 1 + joint6: + p: 100 + d: 1 + i: 1 + i_clamp: 1 \ No newline at end of file diff --git a/mobile_manipulator/mobile_manipulator_config_v1/config/sensors_3d.yaml b/mobile_manipulator/mobile_manipulator_config_v1/config/sensors_3d.yaml new file mode 100644 index 0000000..c0062e1 --- /dev/null +++ b/mobile_manipulator/mobile_manipulator_config_v1/config/sensors_3d.yaml @@ -0,0 +1,26 @@ +sensors: + - sensor_plugin: occupancy_map_monitor/PointCloudOctomapUpdater + point_cloud_topic: /camera1/points + max_range: 5.0 + point_subsample: 1 + padding_offset: 0.1 + padding_scale: 1.0 + max_update_rate: 1.0 + filtered_cloud_topic: /camera1/filtered_cloud + - sensor_plugin: occupancy_map_monitor/PointCloudOctomapUpdater + point_cloud_topic: /camera2/points + max_range: 5.0 + point_subsample: 1 + padding_offset: 0.1 + padding_scale: 1.0 + max_update_rate: 1.0 + filtered_cloud_topic: /camera2/filtered_cloud +# - sensor_plugin: occupancy_map_monitor/PointCloudOctomapUpdater +# point_cloud_topic: depthcam2/points +# max_range: 5.0 +# point_subsample: 1 +# padding_offset: 0.1 +# padding_scale: 1.0 +# max_update_rate: 1.0 +# filtered_cloud_topic: filtered_cloud2 +# [] diff --git a/mobile_manipulator/mobile_manipulator_config_v1/config/simple_moveit_controllers.yaml b/mobile_manipulator/mobile_manipulator_config_v1/config/simple_moveit_controllers.yaml new file mode 100644 index 0000000..3e0113c --- /dev/null +++ b/mobile_manipulator/mobile_manipulator_config_v1/config/simple_moveit_controllers.yaml @@ -0,0 +1,12 @@ +controller_list: + - name: manipulator_controller + action_ns: follow_joint_trajectory + type: FollowJointTrajectory + default: True + joints: + - joint1 + - joint2 + - joint3 + - joint4 + - joint5 + - joint6 \ No newline at end of file diff --git a/mobile_manipulator/mobile_manipulator_config_v1/config/stomp_planning.yaml b/mobile_manipulator/mobile_manipulator_config_v1/config/stomp_planning.yaml new file mode 100644 index 0000000..5484a97 --- /dev/null +++ b/mobile_manipulator/mobile_manipulator_config_v1/config/stomp_planning.yaml @@ -0,0 +1,39 @@ +stomp/manipulator: + group_name: manipulator + optimization: + num_timesteps: 60 + num_iterations: 40 + num_iterations_after_valid: 0 + num_rollouts: 30 + max_rollouts: 30 + initialization_method: 1 # [1 : LINEAR_INTERPOLATION, 2 : CUBIC_POLYNOMIAL, 3 : MININUM_CONTROL_COST] + control_cost_weight: 0.0 + task: + noise_generator: + - class: stomp_moveit/NormalDistributionSampling + stddev: [0.05, 0.05, 0.05, 0.05, 0.05, 0.05] + cost_functions: + - class: stomp_moveit/CollisionCheck + collision_penalty: 1.0 + cost_weight: 1.0 + kernel_window_percentage: 0.2 + longest_valid_joint_move: 0.05 + noisy_filters: + - class: stomp_moveit/JointLimits + lock_start: True + lock_goal: True + - class: stomp_moveit/MultiTrajectoryVisualization + line_width: 0.02 + rgb: [255, 255, 0] + marker_array_topic: stomp_trajectories + marker_namespace: noisy + update_filters: + - class: stomp_moveit/PolynomialSmoother + poly_order: 6 + - class: stomp_moveit/TrajectoryVisualization + line_width: 0.05 + rgb: [0, 191, 255] + error_rgb: [255, 0, 0] + publish_intermediate: True + marker_topic: stomp_trajectory + marker_namespace: optimized \ No newline at end of file diff --git a/mobile_manipulator/mobile_manipulator_config_v1/launch/chomp_planning_pipeline.launch.xml b/mobile_manipulator/mobile_manipulator_config_v1/launch/chomp_planning_pipeline.launch.xml new file mode 100644 index 0000000..7c9b794 --- /dev/null +++ b/mobile_manipulator/mobile_manipulator_config_v1/launch/chomp_planning_pipeline.launch.xml @@ -0,0 +1,23 @@ + + + + + + + + + + + + + + + + diff --git a/mobile_manipulator/mobile_manipulator_config_v1/launch/default_warehouse_db.launch b/mobile_manipulator/mobile_manipulator_config_v1/launch/default_warehouse_db.launch new file mode 100644 index 0000000..cb2b8d9 --- /dev/null +++ b/mobile_manipulator/mobile_manipulator_config_v1/launch/default_warehouse_db.launch @@ -0,0 +1,15 @@ + + + + + + + + + + + + + + + diff --git a/mobile_manipulator/mobile_manipulator_config_v1/launch/demo.launch b/mobile_manipulator/mobile_manipulator_config_v1/launch/demo.launch new file mode 100644 index 0000000..967380b --- /dev/null +++ b/mobile_manipulator/mobile_manipulator_config_v1/launch/demo.launch @@ -0,0 +1,68 @@ + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + [move_group/fake_controller_joint_states] + + + + [move_group/fake_controller_joint_states] + + + + + + + + + + + + + + + + + + + + + + + + + + + + + diff --git a/mobile_manipulator/mobile_manipulator_config_v1/launch/demo_gazebo.launch b/mobile_manipulator/mobile_manipulator_config_v1/launch/demo_gazebo.launch new file mode 100644 index 0000000..a9f320c --- /dev/null +++ b/mobile_manipulator/mobile_manipulator_config_v1/launch/demo_gazebo.launch @@ -0,0 +1,21 @@ + + + + + + + + + + + + + + + + + + + + + diff --git a/mobile_manipulator/mobile_manipulator_config_v1/launch/fake_moveit_controller_manager.launch.xml b/mobile_manipulator/mobile_manipulator_config_v1/launch/fake_moveit_controller_manager.launch.xml new file mode 100644 index 0000000..cddb173 --- /dev/null +++ b/mobile_manipulator/mobile_manipulator_config_v1/launch/fake_moveit_controller_manager.launch.xml @@ -0,0 +1,12 @@ + + + + + + + + + + + + diff --git a/mobile_manipulator/mobile_manipulator_config_v1/launch/gazebo.launch b/mobile_manipulator/mobile_manipulator_config_v1/launch/gazebo.launch new file mode 100644 index 0000000..4c478cc --- /dev/null +++ b/mobile_manipulator/mobile_manipulator_config_v1/launch/gazebo.launch @@ -0,0 +1,37 @@ + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + diff --git a/mobile_manipulator/mobile_manipulator_config_v1/launch/joystick_control.launch b/mobile_manipulator/mobile_manipulator_config_v1/launch/joystick_control.launch new file mode 100644 index 0000000..9411f6e --- /dev/null +++ b/mobile_manipulator/mobile_manipulator_config_v1/launch/joystick_control.launch @@ -0,0 +1,17 @@ + + + + + + + + + + + + + + + + + diff --git a/mobile_manipulator/mobile_manipulator_config_v1/launch/move_group.launch b/mobile_manipulator/mobile_manipulator_config_v1/launch/move_group.launch new file mode 100644 index 0000000..76443a4 --- /dev/null +++ b/mobile_manipulator/mobile_manipulator_config_v1/launch/move_group.launch @@ -0,0 +1,101 @@ + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + diff --git a/mobile_manipulator/mobile_manipulator_config_v1/launch/moveit.rviz b/mobile_manipulator/mobile_manipulator_config_v1/launch/moveit.rviz new file mode 100644 index 0000000..2530b2d --- /dev/null +++ b/mobile_manipulator/mobile_manipulator_config_v1/launch/moveit.rviz @@ -0,0 +1,177 @@ +Panels: + - Class: rviz/Displays + Help Height: 84 + Name: Displays + Property Tree Widget: + Expanded: + - /MotionPlanning1 + Splitter Ratio: 0.5 + Tree Height: 226 + - Class: rviz/Help + Name: Help + - Class: rviz/Views + Expanded: + - /Current View1 + Name: Views + Splitter Ratio: 0.5 +Preferences: + PromptSaveOnExit: true +Toolbars: + toolButtonStyle: 2 +Visualization Manager: + Class: "" + Displays: + - Alpha: 0.5 + Cell Size: 1 + Class: rviz/Grid + Color: 160; 160; 164 + Enabled: true + Line Style: + Line Width: 0.029999999329447746 + Value: Lines + Name: Grid + Normal Cell Count: 0 + Offset: + X: 0 + Y: 0 + Z: 0 + Plane: XY + Plane Cell Count: 10 + Reference Frame: + Value: true + - Acceleration_Scaling_Factor: 0.1 + Class: moveit_rviz_plugin/MotionPlanning + Enabled: true + Move Group Namespace: "" + MoveIt_Allow_Approximate_IK: false + MoveIt_Allow_External_Program: false + MoveIt_Allow_Replanning: false + MoveIt_Allow_Sensor_Positioning: false + MoveIt_Planning_Attempts: 10 + MoveIt_Planning_Time: 5 + MoveIt_Use_Cartesian_Path: false + MoveIt_Use_Constraint_Aware_IK: false + MoveIt_Workspace: + Center: + X: 0 + Y: 0 + Z: 0 + Size: + X: 2 + Y: 2 + Z: 2 + Name: MotionPlanning + Planned Path: + Color Enabled: false + Interrupt Display: false + Links: + All Links Enabled: true + Expand Joint Details: false + Expand Link Details: false + Expand Tree: false + Link Tree Style: "" + Loop Animation: true + Robot Alpha: 0.5 + Robot Color: 150; 50; 150 + Show Robot Collision: false + Show Robot Visual: true + Show Trail: false + State Display Time: 0.05 s + Trail Step Size: 1 + Trajectory Topic: move_group/display_planned_path + Use Sim Time: false + Planning Metrics: + Payload: 1 + Show Joint Torques: false + Show Manipulability: false + Show Manipulability Index: false + Show Weight Limit: false + TextHeight: 0.07999999821186066 + Planning Request: + Colliding Link Color: 255; 0; 0 + Goal State Alpha: 1 + Goal State Color: 250; 128; 0 + Interactive Marker Size: 0 + Joint Violation Color: 255; 0; 255 + Planning Group: "" + Query Goal State: true + Query Start State: false + Show Workspace: false + Start State Alpha: 1 + Start State Color: 0; 255; 0 + Planning Scene Topic: move_group/monitored_planning_scene + Robot Description: robot_description + Scene Geometry: + Scene Alpha: 1 + Scene Color: 50; 230; 50 + Scene Display Time: 0.009999999776482582 + Show Scene Geometry: true + Voxel Coloring: Z-Axis + Voxel Rendering: Occupied Voxels + Scene Robot: + Attached Body Color: 150; 50; 150 + Links: + All Links Enabled: true + Expand Joint Details: false + Expand Link Details: false + Expand Tree: false + Link Tree Style: "" + Robot Alpha: 0.5 + Show Robot Collision: false + Show Robot Visual: true + Value: true + Velocity_Scaling_Factor: 0.1 + Enabled: true + Global Options: + Background Color: 48; 48; 48 + Default Light: true + Fixed Frame: ota_base_link + Frame Rate: 30 + Name: root + Tools: + - Class: rviz/Interact + Hide Inactive Objects: true + - Class: rviz/MoveCamera + - Class: rviz/Select + Value: true + Views: + Current: + Class: rviz/Orbit + Distance: 2 + Enable Stereo Rendering: + Stereo Eye Separation: 0.05999999865889549 + Stereo Focal Distance: 1 + Swap Stereo Eyes: false + Value: false + Field of View: 0.75 + Focal Point: + X: -0.10000000149011612 + Y: 0.25 + Z: 0.30000001192092896 + Focal Shape Fixed Size: true + Focal Shape Size: 0.05000000074505806 + Invert Z Axis: false + Name: Current View + Near Clip Distance: 0.009999999776482582 + Pitch: 0.5 + Target Frame: ota_base_link + Yaw: -0.6232355833053589 + Saved: ~ +Window Geometry: + Displays: + collapsed: false + Height: 848 + Help: + collapsed: false + Hide Left Dock: false + Hide Right Dock: false + MotionPlanning: + collapsed: false + MotionPlanning - Trajectory Slider: + collapsed: false + QMainWindow State: 000000ff00000000fd0000000100000000000001f3000002f6fc0200000007fb000000100044006900730070006c006100790073010000003d00000173000000c900fffffffb0000000800480065006c00700000000342000000bb0000006e00fffffffb0000000a00560069006500770073000000010c000000a4000000a400fffffffb0000000c00430061006d00650072006100000002ff000001610000000000000000fb0000001e004d006f00740069006f006e00200050006c0061006e006e0069006e00670100000374000001890000000000000000fb00000044004d006f00740069006f006e0050006c0061006e006e0069006e00670020002d0020005400720061006a006500630074006f0072007900200053006c00690064006500720000000000ffffffff0000001600000016fb0000001c004d006f00740069006f006e0050006c0061006e006e0069006e006701000001b60000017d0000017d00ffffff00000312000002f600000001000000020000000100000002fc0000000100000002000000010000000a0054006f006f006c00730100000000ffffffff0000000000000000 + Views: + collapsed: false + Width: 1291 + X: 454 + Y: 27 diff --git a/mobile_manipulator/mobile_manipulator_config_v1/launch/moveit_rviz.launch b/mobile_manipulator/mobile_manipulator_config_v1/launch/moveit_rviz.launch new file mode 100644 index 0000000..a4605c0 --- /dev/null +++ b/mobile_manipulator/mobile_manipulator_config_v1/launch/moveit_rviz.launch @@ -0,0 +1,15 @@ + + + + + + + + + + + + + + diff --git a/mobile_manipulator/mobile_manipulator_config_v1/launch/ompl-chomp_planning_pipeline.launch.xml b/mobile_manipulator/mobile_manipulator_config_v1/launch/ompl-chomp_planning_pipeline.launch.xml new file mode 100644 index 0000000..b078992 --- /dev/null +++ b/mobile_manipulator/mobile_manipulator_config_v1/launch/ompl-chomp_planning_pipeline.launch.xml @@ -0,0 +1,19 @@ + + + + + + + + + + + + diff --git a/mobile_manipulator/mobile_manipulator_config_v1/launch/ompl_planning_pipeline.launch.xml b/mobile_manipulator/mobile_manipulator_config_v1/launch/ompl_planning_pipeline.launch.xml new file mode 100644 index 0000000..2306900 --- /dev/null +++ b/mobile_manipulator/mobile_manipulator_config_v1/launch/ompl_planning_pipeline.launch.xml @@ -0,0 +1,26 @@ + + + + + + + + + + + + + + + + + + + diff --git a/mobile_manipulator/mobile_manipulator_config_v1/launch/pilz_industrial_motion_planner_planning_pipeline.launch.xml b/mobile_manipulator/mobile_manipulator_config_v1/launch/pilz_industrial_motion_planner_planning_pipeline.launch.xml new file mode 100644 index 0000000..c7c4cf5 --- /dev/null +++ b/mobile_manipulator/mobile_manipulator_config_v1/launch/pilz_industrial_motion_planner_planning_pipeline.launch.xml @@ -0,0 +1,15 @@ + + + + + + + + + + + + + + diff --git a/mobile_manipulator/mobile_manipulator_config_v1/launch/planning_context.launch b/mobile_manipulator/mobile_manipulator_config_v1/launch/planning_context.launch new file mode 100644 index 0000000..1b42262 --- /dev/null +++ b/mobile_manipulator/mobile_manipulator_config_v1/launch/planning_context.launch @@ -0,0 +1,26 @@ + + + + + + + + + + + + + + + + + + + + + + + + + + diff --git a/mobile_manipulator/mobile_manipulator_config_v1/launch/planning_pipeline.launch.xml b/mobile_manipulator/mobile_manipulator_config_v1/launch/planning_pipeline.launch.xml new file mode 100644 index 0000000..4b4d0d6 --- /dev/null +++ b/mobile_manipulator/mobile_manipulator_config_v1/launch/planning_pipeline.launch.xml @@ -0,0 +1,10 @@ + + + + + + + + + diff --git a/mobile_manipulator/mobile_manipulator_config_v1/launch/robot_description.launch b/mobile_manipulator/mobile_manipulator_config_v1/launch/robot_description.launch new file mode 100644 index 0000000..a12df9c --- /dev/null +++ b/mobile_manipulator/mobile_manipulator_config_v1/launch/robot_description.launch @@ -0,0 +1,11 @@ + + + + + + + + + + + diff --git a/mobile_manipulator/mobile_manipulator_config_v1/launch/robot_moveit_sensor_manager.launch.xml b/mobile_manipulator/mobile_manipulator_config_v1/launch/robot_moveit_sensor_manager.launch.xml new file mode 100644 index 0000000..5d02698 --- /dev/null +++ b/mobile_manipulator/mobile_manipulator_config_v1/launch/robot_moveit_sensor_manager.launch.xml @@ -0,0 +1,3 @@ + + + diff --git a/mobile_manipulator/mobile_manipulator_config_v1/launch/ros_control_moveit_controller_manager.launch.xml b/mobile_manipulator/mobile_manipulator_config_v1/launch/ros_control_moveit_controller_manager.launch.xml new file mode 100644 index 0000000..9ebc91c --- /dev/null +++ b/mobile_manipulator/mobile_manipulator_config_v1/launch/ros_control_moveit_controller_manager.launch.xml @@ -0,0 +1,4 @@ + + + + diff --git a/mobile_manipulator/mobile_manipulator_config_v1/launch/ros_controllers.launch b/mobile_manipulator/mobile_manipulator_config_v1/launch/ros_controllers.launch new file mode 100644 index 0000000..80b8b8a --- /dev/null +++ b/mobile_manipulator/mobile_manipulator_config_v1/launch/ros_controllers.launch @@ -0,0 +1,11 @@ + + + + + + + + + + diff --git a/mobile_manipulator/mobile_manipulator_config_v1/launch/run_benchmark_ompl.launch b/mobile_manipulator/mobile_manipulator_config_v1/launch/run_benchmark_ompl.launch new file mode 100644 index 0000000..febde2a --- /dev/null +++ b/mobile_manipulator/mobile_manipulator_config_v1/launch/run_benchmark_ompl.launch @@ -0,0 +1,21 @@ + + + + + + + + + + + + + + + + + + + + + diff --git a/mobile_manipulator/mobile_manipulator_config_v1/launch/sensor_manager.launch.xml b/mobile_manipulator/mobile_manipulator_config_v1/launch/sensor_manager.launch.xml new file mode 100644 index 0000000..0e291bb --- /dev/null +++ b/mobile_manipulator/mobile_manipulator_config_v1/launch/sensor_manager.launch.xml @@ -0,0 +1,17 @@ + + + + + + + + + + + + + + + + + diff --git a/mobile_manipulator/mobile_manipulator_config_v1/launch/setup_assistant.launch b/mobile_manipulator/mobile_manipulator_config_v1/launch/setup_assistant.launch new file mode 100644 index 0000000..d598725 --- /dev/null +++ b/mobile_manipulator/mobile_manipulator_config_v1/launch/setup_assistant.launch @@ -0,0 +1,16 @@ + + + + + + + + + + + + diff --git a/mobile_manipulator/mobile_manipulator_config_v1/launch/simple_moveit_controller_manager.launch.xml b/mobile_manipulator/mobile_manipulator_config_v1/launch/simple_moveit_controller_manager.launch.xml new file mode 100644 index 0000000..9d35646 --- /dev/null +++ b/mobile_manipulator/mobile_manipulator_config_v1/launch/simple_moveit_controller_manager.launch.xml @@ -0,0 +1,8 @@ + + + + + + + + diff --git a/mobile_manipulator/mobile_manipulator_config_v1/launch/stomp_planning_pipeline.launch.xml b/mobile_manipulator/mobile_manipulator_config_v1/launch/stomp_planning_pipeline.launch.xml new file mode 100644 index 0000000..b9f72b0 --- /dev/null +++ b/mobile_manipulator/mobile_manipulator_config_v1/launch/stomp_planning_pipeline.launch.xml @@ -0,0 +1,25 @@ + + + + + + + + + + + + + + + + + + + + diff --git a/mobile_manipulator/mobile_manipulator_config_v1/launch/trajectory_execution.launch.xml b/mobile_manipulator/mobile_manipulator_config_v1/launch/trajectory_execution.launch.xml new file mode 100644 index 0000000..20c3dfc --- /dev/null +++ b/mobile_manipulator/mobile_manipulator_config_v1/launch/trajectory_execution.launch.xml @@ -0,0 +1,23 @@ + + + + + + + + + + + + + + + + + + + + + + diff --git a/mobile_manipulator/mobile_manipulator_config_v1/launch/warehouse.launch b/mobile_manipulator/mobile_manipulator_config_v1/launch/warehouse.launch new file mode 100644 index 0000000..0712e67 --- /dev/null +++ b/mobile_manipulator/mobile_manipulator_config_v1/launch/warehouse.launch @@ -0,0 +1,15 @@ + + + + + + + + + + + + + + + diff --git a/mobile_manipulator/mobile_manipulator_config_v1/launch/warehouse_settings.launch.xml b/mobile_manipulator/mobile_manipulator_config_v1/launch/warehouse_settings.launch.xml new file mode 100644 index 0000000..e473b08 --- /dev/null +++ b/mobile_manipulator/mobile_manipulator_config_v1/launch/warehouse_settings.launch.xml @@ -0,0 +1,16 @@ + + + + + + + + + + + + + + + + diff --git a/mobile_manipulator/mobile_manipulator_config_v1/package.xml b/mobile_manipulator/mobile_manipulator_config_v1/package.xml new file mode 100644 index 0000000..cf9e581 --- /dev/null +++ b/mobile_manipulator/mobile_manipulator_config_v1/package.xml @@ -0,0 +1,41 @@ + + + mobile_manipulator_config_v1 + 0.3.0 + + An automatically generated package with all the configuration and launch files for using the robot with the MoveIt Motion Planning Framework + + didem + didem + + BSD + + http://moveit.ros.org/ + https://github.com/ros-planning/moveit/issues + https://github.com/ros-planning/moveit + + catkin + + moveit_ros_move_group + moveit_fake_controller_manager + moveit_kinematics + moveit_planners_ompl + moveit_ros_visualization + moveit_setup_assistant + moveit_simple_controller_manager + joint_state_publisher + joint_state_publisher_gui + robot_state_publisher + rviz + tf2_ros + xacro + + + + + + mobile_manipulator_description + + + diff --git a/mobile_manipulator/mobile_manipulator_config_v1/world/ifarlab_value3s.world b/mobile_manipulator/mobile_manipulator_config_v1/world/ifarlab_value3s.world new file mode 100644 index 0000000..e969616 --- /dev/null +++ b/mobile_manipulator/mobile_manipulator_config_v1/world/ifarlab_value3s.world @@ -0,0 +1,1818 @@ + + + + 1 + 0 0 10 0 -0 0 + 0.8 0.8 0.8 1 + 0.2 0.2 0.2 1 + + 1000 + 0.9 + 0.01 + 0.001 + + -0.5 0.1 -0.9 + + 0 + 0 + 0 + + + + 1 + + + + + 0 0 1 + 100 100 + + + + + 65535 + + + + + 100 + 50 + + + + + + + + 10 + + + 0 + + + 0 0 1 + 100 100 + + + + + + + 0 + 0 + 0 + + + 0 0 -9.8 + 6e-06 2.3e-05 -4.2e-05 + + + 0.001 + 1 + 1000 + + + 0.4 0.4 0.4 1 + 0.7 0.7 0.7 1 + 1 + + + + EARTH_WGS84 + 0 + 0 + 0 + 0 + + + + + 1 + + 0.166667 + 0 + 0 + 0.166667 + 0 + 0.166667 + + 0 0 0 0 -0 0 + + 0 0 0 0 -0 0 + 1 + 0 + 0 + 0 + + 0.4 -1.28 0 0 -0 0 + + + model://ifarlab_ray/model/ifarlab_ray.stl + 0.001 0.001 0.001 + + + 0 + 1 + + + 0 + 10 + 0.4 -1.28 0 0 -0 0 + + + model://ifarlab_ray/model/ifarlab_ray.stl + 0.001 0.001 0.001 + + + + + + 1 + 1 + 0 0 0 + 0 + 0 + + + 1 + 0 + 0 + 1 + + 0 + + + + + 0 + 1e+06 + + + 0 + 1 + 1 + + 0 + 0.2 + 1e+13 + 1 + 0.01 + 0 + + + 1 + -0.01 + 0 + 0.2 + 1e+13 + 1 + + + + + + 1 + 1 + 0.143566 -1.4213 0 0 -0 0 + + + + + 1 + + 0.166667 + 0 + 0 + 0.166667 + 0 + 0.166667 + + 0 0 0 0 -0 0 + + 0 0 0 0 -0 0 + 1 + 0 + 0 + 0 + + -0.92725 1.7723 0 0 -0 0 + + + model://light_curtain/model/light_curtain.stl + 0.001 0.001 0.001 + + + 0 + 1 + + + 0 + 10 + -0.92725 1.7723 0 0 -0 0 + + + model://light_curtain/model/light_curtain.stl + 0.001 0.001 0.001 + + + + + + 1 + 1 + 0 0 0 + 0 + 0 + + + 1 + 0 + 0 + 1 + + 0 + + + + + 0 + 1e+06 + + + 0 + 1 + 1 + + 0 + 0.2 + 1e+13 + 1 + 0.01 + 0 + + + 1 + -0.01 + 0 + 0.2 + 1e+13 + 1 + + + + + + -0.605 0 0.22 0 -0 0 + + + + -0.001 + 0.001 + 640 + 1 + + + 1 + 0 + 0 + + + + 0.001 + 1.5 + + + + ir + link + link + infrared + + 1 + 4 + 1 + + + -0.605 0 0.32 0 -0 0 + + + + -0.001 + 0.001 + 640 + 1 + + + 1 + 0 + 0 + + + + 0.001 + 1.5 + 0.001 + + + + ir1 + link + link + infrared + + 1 + 4 + 1 + + + -0.605 0 0.42 0 -0 0 + + + + -0.001 + 0.001 + 640 + 1 + + + 1 + 0 + 0 + + + + 0.001 + 1.5 + 0.001 + + + + ir2 + link + link + infrared + + 1 + 4 + 1 + + + -0.605 0 0.52 0 -0 0 + + + + 320 + 1 + -0.001 + 0.001 + + + 1 + 0 + 0 + + + + 0.001 + 1.5 + 0.001 + + + + ir3 + link + link + infrared + + 1 + 4 + 1 + + + -0.605 0 0.62 0 -0 0 + + + + -0.001 + 0.001 + 640 + 1 + + + 1 + 0 + 0 + + + + 0.001 + 1.5 + 0.001 + + + + ir4 + link + link + infrared + + 1 + 4 + 1 + + + -0.605 0 0.72 0 -0 0 + + + + -0.001 + 0.001 + 640 + 1 + + + 1 + 0 + 0 + + + + 0.001 + 1.5 + 0.001 + + + + ir5 + link + link + infrared + + 1 + 4 + 1 + + + -0.605 0 0.82 0 -0 0 + + + + -0.001 + 0.001 + 640 + 1 + + + 1 + 0 + 0 + + + + 0.001 + 1.5 + 0.001 + + + + ir6 + link + link + infrared + + 1 + 4 + 1 + + + -0.605 0 0.92 0 -0 0 + + + + -0.001 + 0.001 + 640 + 1 + + + 1 + 0 + 0 + + + + 0.001 + 1.5 + 0.001 + + + + ir7 + link + link + infrared + + 1 + 4 + 1 + + + -0.605 0 1.02 0 -0 0 + + + + -0.001 + 0.001 + 640 + 1 + + + 1 + 0 + 0 + + + + 0.001 + 1.5 + 0.001 + + + + ir8 + link + link + infrared + + 1 + 4 + 1 + + + 1 + 1 + 2.80566 -1.32602 0 0 -0 0 + + + + + 1 + + 0.166667 + 0 + 0 + 0.166667 + 0 + 0.166667 + + 0 0 0 0 -0 0 + + 0 0 0 0 -0 0 + 1 + 0 + 0 + 0 + + 0.7 -3.7 0 0 -0 0 + + + model://kabinet/model/Kabinet.stl + 0.001 0.001 0.00125 + + + 0 + 1 + + + 0 + 10 + 0.7 3.7 0 0 -0 0 + + + model://kabinet/model/Kabinet.stl + 0.001 0.001 0.00125 + + + + + + 1 + 1 + 0 0 0 + 0 + 0 + + + 1 + 0 + 0 + 1 + + 0 + + + + + 0 + 1e+06 + + + 0 + 1 + 1 + + 0 + 0.2 + 1e+13 + 1 + 0.01 + 0 + + + 1 + -0.01 + 0 + 0.2 + 1e+13 + 1 + + + + + + 1 + 1 + -0.742257 -2.41133 0 0 0 -1.5708 + + + + + 1 + + 0.166667 + 0 + 0 + 0.166667 + 0 + 0.166667 + + 0 0 0 0 -0 0 + + 0 0 0 0 -0 0 + 1 + 0 + 0 + 0 + + 1.085 0.4 0 0 -0 0 + + + model://barrier/model/barrier.stl + 0.001 0.001 0.001 + + + 0 + 1 + + + 0 + 10 + 1.085 0.4 0 0 -0 0 + + + model://barrier/model/barrier.stl + 0.001 0.001 0.001 + + + + + + 1 + 1 + 0 0 0 + 0 + 0 + + + 1 + 0 + 0 + 1 + + 0 + + + + + 0 + 1e+06 + + + 0 + 1 + 1 + + 0 + 0.2 + 1e+13 + 1 + 0.01 + 0 + + + 1 + -0.01 + 0 + 0.2 + 1e+13 + 1 + + + + + + 1 + 1 + -0.36548 2.02914 0 0 -0 0 + + + + + 1 + + 0.166667 + 0 + 0 + 0.166667 + 0 + 0.166667 + + 0 0 0 0 -0 0 + + 0 0 0 0 -0 0 + 1 + 0 + 0 + 0 + + 1.085 0.4 0 0 -0 0 + + + model://barrier/model/barrier.stl + 0.001 0.001 0.001 + + + 0 + 1 + + + 0 + 10 + 1.085 0.4 0 0 -0 0 + + + model://barrier/model/barrier.stl + 0.001 0.001 0.001 + + + + + + 1 + 1 + 0 0 0 + 0 + 0 + + + 1 + 0 + 0 + 1 + + 0 + + + + + 0 + 1e+06 + + + 0 + 1 + 1 + + 0 + 0.2 + 1e+13 + 1 + 0.01 + 0 + + + 1 + -0.01 + 0 + 0.2 + 1e+13 + 1 + + + + + + 1 + 1 + 0.811401 2 0 0 -0 -3.14159 + + + + + 1 + + 0.166667 + 0 + 0 + 0.166667 + 0 + 0.166667 + + 0 0 0 0 -0 0 + + 0 0 0 0 -0 0 + 1 + 0 + 0 + 0 + + 1.085 0.4 0 0 -0 0 + + + model://barrier/model/barrier.stl + 0.001 0.001 0.001 + + + 0 + 1 + + + 0 + 10 + 1.085 0.4 0 0 -0 0 + + + model://barrier/model/barrier.stl + 0.001 0.001 0.001 + + + + + + 1 + 1 + 0 0 0 + 0 + 0 + + + 1 + 0 + 0 + 1 + + 0 + + + + + 0 + 1e+06 + + + 0 + 1 + 1 + + 0 + 0.2 + 1e+13 + 1 + 0.01 + 0 + + + 1 + -0.01 + 0 + 0.2 + 1e+13 + 1 + + + + + + 1 + 1 + 2 2 0 0 -0 -3.14159 + + + + + 1 + + 0.166667 + 0 + 0 + 0.166667 + 0 + 0.166667 + + 0 0 0 0 -0 0 + + 0 0 0 0 -0 0 + 1 + 0 + 0 + 0 + + 1.085 0.4 0 0 -0 0 + + + model://barrier/model/barrier.stl + 0.001 0.001 0.001 + + + 0 + 1 + + + 0 + 10 + 1.085 0.4 0 0 -0 0 + + + model://barrier/model/barrier.stl + 0.001 0.001 0.001 + + + + + + 1 + 1 + 0 0 0 + 0 + 0 + + + 1 + 0 + 0 + 1 + + 0 + + + + + 0 + 1e+06 + + + 0 + 1 + 1 + + 0 + 0.2 + 1e+13 + 1 + 0.01 + 0 + + + 1 + -0.01 + 0 + 0.2 + 1e+13 + 1 + + + + + + 1 + 1 + -0.404037 -1.95 0 0 -0 0 + + + + + 1 + + 0.166667 + 0 + 0 + 0.166667 + 0 + 0.166667 + + 0 0 0 0 -0 0 + + 0 0 0 0 -0 0 + 1 + 0 + 0 + 0 + + 1.085 0.4 0 0 -0 0 + + + model://barrier/model/barrier.stl + 0.001 0.001 0.001 + + + 0 + 1 + + + 0 + 10 + 1.085 0.4 0 0 -0 0 + + + model://barrier/model/barrier.stl + 0.001 0.001 0.001 + + + + + + 1 + 1 + 0 0 0 + 0 + 0 + + + 1 + 0 + 0 + 1 + + 0 + + + + + 0 + 1e+06 + + + 0 + 1 + 1 + + 0 + 0.2 + 1e+13 + 1 + 0.01 + 0 + + + 1 + -0.01 + 0 + 0.2 + 1e+13 + 1 + + + + + + 1 + 1 + -0.966612 1.34 0 0 0 -1.5708 + + + + + 1 + + 0.166667 + 0 + 0 + 0.166667 + 0 + 0.166667 + + 0 0 0 0 -0 0 + + 0 0 0 0 -0 0 + 1 + 0 + 0 + 0 + + 1.085 0.4 0 0 -0 0 + + + model://barrier/model/barrier.stl + 0.001 0.001 0.001 + + + 0 + 1 + + + 0 + 10 + 1.085 0.4 0 0 -0 0 + + + model://barrier/model/barrier.stl + 0.001 0.001 0.001 + + + + + + 1 + 1 + 0 0 0 + 0 + 0 + + + 1 + 0 + 0 + 1 + + 0 + + + + + 0 + 1e+06 + + + 0 + 1 + 1 + + 0 + 0.2 + 1e+13 + 1 + 0.01 + 0 + + + 1 + -0.01 + 0 + 0.2 + 1e+13 + 1 + + + + + + 1 + 1 + -0.95 0.04 0 0 0 -1.5708 + + + + + 1 + + 0.166667 + 0 + 0 + 0.166667 + 0 + 0.166667 + + 0 0 0 0 -0 0 + + 0 0 0 0 -0 0 + 1 + 0 + 0 + 0 + + 1.085 0.4 0 0 -0 0 + + + model://barrier/model/barrier.stl + 0.001 0.001 0.001 + + + 0 + 1 + + + 0 + 10 + 1.085 0.4 0 0 -0 0 + + + model://barrier/model/barrier.stl + 0.001 0.001 0.001 + + + + + + 1 + 1 + 0 0 0 + 0 + 0 + + + 1 + 0 + 0 + 1 + + 0 + + + + + 0 + 1e+06 + + + 0 + 1 + 1 + + 0 + 0.2 + 1e+13 + 1 + 0.01 + 0 + + + 1 + -0.01 + 0 + 0.2 + 1e+13 + 1 + + + + + + 1 + 1 + -0.947469 -1.26 0 0 0 -1.5708 + + + + + 1 + + 0.166667 + 0 + 0 + 0.166667 + 0 + 0.166667 + + 0 0 0 0 -0 0 + + 0 0 0 0 -0 0 + 1 + 0 + 0 + 0 + + 1.085 0.4 0 0 -0 0 + + + model://barrier/model/barrier.stl + 0.001 0.001 0.001 + + + 0 + 1 + + + 0 + 10 + 1.085 0.4 0 0 -0 0 + + + model://barrier/model/barrier.stl + 0.001 0.001 0.001 + + + + + + 1 + 1 + 0 0 0 + 0 + 0 + + + 1 + 0 + 0 + 1 + + 0 + + + + + 0 + 1e+06 + + + 0 + 1 + 1 + + 0 + 0.2 + 1e+13 + 1 + 0.01 + 0 + + + 1 + -0.01 + 0 + 0.2 + 1e+13 + 1 + + + + + + 1 + 1 + 2.5 -1.26 0 0 -0 1.5708 + + + + + 1 + + 0.166667 + 0 + 0 + 0.166667 + 0 + 0.166667 + + 0 0 0 0 -0 0 + + 0 0 0 0 -0 0 + 1 + 0 + 0 + 0 + + 1.085 0.4 0 0 -0 0 + + + model://barrier/model/barrier.stl + 0.001 0.001 0.001 + + + 0 + 1 + + + 0 + 10 + 1.085 0.4 0 0 -0 0 + + + model://barrier/model/barrier.stl + 0.001 0.001 0.001 + + + + + + 1 + 1 + 0 0 0 + 0 + 0 + + + 1 + 0 + 0 + 1 + + 0 + + + + + 0 + 1e+06 + + + 0 + 1 + 1 + + 0 + 0.2 + 1e+13 + 1 + 0.01 + 0 + + + 1 + -0.01 + 0 + 0.2 + 1e+13 + 1 + + + + + + 1 + 1 + 2.5 0.04 0 0 -0 1.5708 + + + + + 1 + + 0.166667 + 0 + 0 + 0.166667 + 0 + 0.166667 + + 0 0 0 0 -0 0 + + 0 0 0 0 -0 0 + 1 + 0 + 0 + 0 + + 1.085 0.4 0 0 -0 0 + + + model://barrier/model/barrier.stl + 0.001 0.001 0.001 + + + 0 + 1 + + + 0 + 10 + 1.085 0.4 0 0 -0 0 + + + model://barrier/model/barrier.stl + 0.001 0.001 0.001 + + + + + + 1 + 1 + 0 0 0 + 0 + 0 + + + 1 + 0 + 0 + 1 + + 0 + + + + + 0 + 1e+06 + + + 0 + 1 + 1 + + 0 + 0.2 + 1e+13 + 1 + 0.01 + 0 + + + 1 + -0.01 + 0 + 0.2 + 1e+13 + 1 + + + + + + 1 + 1 + 2.5 1.34 0 0 -0 1.5708 + + + + + 1 + + 0.166667 + 0 + 0 + 0.166667 + 0 + 0.166667 + + 0 0 0 0 -0 0 + + 0 0 0 0 -0 0 + 1 + 0 + 0 + 0 + + 1.085 0.4 0 0 -0 0 + + + model://barrier/model/barrier.stl + 0.001 0.001 0.001 + + + 0 + 1 + + + 0 + 10 + 1.085 0.4 0 0 -0 0 + + + model://barrier/model/barrier.stl + 0.001 0.001 0.001 + + + + + + 1 + 1 + 0 0 0 + 0 + 0 + + + 1 + 0 + 0 + 1 + + 0 + + + + + 0 + 1e+06 + + + 0 + 1 + 1 + + 0 + 0.2 + 1e+13 + 1 + 0.01 + 0 + + + 1 + -0.01 + 0 + 0.2 + 1e+13 + 1 + + + + + + 1 + 1 + 1.9807 -1.95 0 0 -0 0 + + + 4062 579000000 + 4426 627338279 + 1671195438 422600337 + 4062579 + + -0.388652 2 0 0 -0 -3.14159 + 1 1 1 + + -0.388652 2 0 0 -0 -3.14159 + 0 0 0 0 -0 0 + 0 0 0 0 -0 0 + 0 0 0 0 -0 0 + + + + 0.811401 2 0 0 -0 -3.14159 + 1 1 1 + + 0.811401 2 0 0 -0 -3.14159 + 0 0 0 0 -0 0 + 0 0 0 0 -0 0 + 0 0 0 0 -0 0 + + + + 2 2 0 0 -0 -3.14159 + 1 1 1 + + 2 2 0 0 -0 -3.14159 + 0 0 0 0 -0 0 + 0 0 0 0 -0 0 + 0 0 0 0 -0 0 + + + + -0.404037 -1.95 0 0 -0 0 + 1 1 1 + + -0.404037 -1.95 0 0 -0 0 + 0 0 0 0 -0 0 + 0 0 0 0 -0 0 + 0 0 0 0 -0 0 + + + + -0.966612 1.34 0 0 0 -1.5708 + 1 1 1 + + -0.966612 1.34 0 0 0 -1.5708 + 0 0 0 0 -0 0 + 0 0 0 0 -0 0 + 0 0 0 0 -0 0 + + + + -0.95 0.04 0 0 0 -1.5708 + 1 1 1 + + -0.95 0.04 0 0 0 -1.5708 + 0 0 0 0 -0 0 + 0 0 0 0 -0 0 + 0 0 0 0 -0 0 + + + + -0.947469 -1.26 0 0 0 -1.5708 + 1 1 1 + + -0.947469 -1.26 0 0 0 -1.5708 + 0 0 0 0 -0 0 + 0 0 0 0 -0 0 + 0 0 0 0 -0 0 + + + + 2.5 -1.26 0 0 -0 1.5708 + 1 1 1 + + 2.5 -1.26 0 0 -0 1.5708 + 0 0 0 0 -0 0 + 0 0 0 0 -0 0 + 0 0 0 0 -0 0 + + + + 2.5 0.04 0 0 -0 1.5708 + 1 1 1 + + 2.5 0.04 0 0 -0 1.5708 + 0 0 0 0 -0 0 + 0 0 0 0 -0 0 + 0 0 0 0 -0 0 + + + + 2.5 1.34 0 0 -0 1.5708 + 1 1 1 + + 2.5 1.34 0 0 -0 1.5708 + 0 0 0 0 -0 0 + 0 0 0 0 -0 0 + 0 0 0 0 -0 0 + + + + 1.9807 -1.95 0 0 -0 0 + 1 1 1 + + 1.9807 -1.95 0 0 -0 0 + 0 0 0 0 -0 0 + 0 0 0 0 -0 0 + 0 0 0 0 -0 0 + + + + 0 0 0 0 -0 0 + 1 1 1 + + 0 0 0 0 -0 0 + 0 0 0 0 -0 0 + 0 0 0 0 -0 0 + 0 0 0 0 -0 0 + + + + 0 0 0 0 -0 3.14159 + 1 1 1 + + 0 0 0 0 -0 3.14159 + 0 0 0 0 -0 0 + 0 0 0 0 -0 0 + 0 0 0 0 -0 0 + + + + -0.742257 -2.41133 0 0 0 -1.5708 + 1 1 1 + + -0.742257 -2.41133 0 0 0 -1.5708 + 0 0 0 0 -0 0 + 0 0 0 0 -0 0 + 0 0 0 0 -0 0 + + + + 0.78522 -2 0 0 -0 0 + 1 1 1 + + 0.78522 -2 0 0 -0 0 + 0 0 0 0 -0 0 + 0 0 0 0 -0 0 + 0 0 0 0 -0 0 + + + + 0 0 10 0 -0 0 + + + + + 1.82247 -5.37137 5.43693 0 0.793791 1.52739 + orbit + perspective + + + + diff --git a/mobile_manipulator/mobile_manipulator_config_v1/world/ifarlab_value3s_v1.world b/mobile_manipulator/mobile_manipulator_config_v1/world/ifarlab_value3s_v1.world new file mode 100644 index 0000000..43ed8a5 --- /dev/null +++ b/mobile_manipulator/mobile_manipulator_config_v1/world/ifarlab_value3s_v1.world @@ -0,0 +1,1926 @@ + + + + 1 + 0 0 10 0 -0 0 + 0.8 0.8 0.8 1 + 0.2 0.2 0.2 1 + + 1000 + 0.9 + 0.01 + 0.001 + + -0.5 0.1 -0.9 + + 0 + 0 + 0 + + + + 1 + + + + + 0 0 1 + 100 100 + + + + + 65535 + + + + + 100 + 50 + + + + + + + + 10 + + + 0 + + + 0 0 1 + 100 100 + + + + + + + 0 + 0 + 0 + + + 0 0 -9.8 + 6e-06 2.3e-05 -4.2e-05 + + + 0.001 + 1 + 1000 + + + 0.4 0.4 0.4 1 + 0.7 0.7 0.7 1 + 1 + + + + EARTH_WGS84 + 0 + 0 + 0 + 0 + + + + + 1 + + 0.166667 + 0 + 0 + 0.166667 + 0 + 0.166667 + + 0 0 0 0 -0 0 + + 0 0 0 0 -0 0 + 1 + 0 + 0 + 0 + + 0.4 -1.28 0 0 -0 0 + + + model://ifarlab_ray/model/ifarlab_ray.stl + 0.001 0.001 0.001 + + + 0 + 1 + + + 0 + 10 + 0.4 -1.28 0 0 -0 0 + + + model://ifarlab_ray/model/ifarlab_ray.stl + 0.001 0.001 0.001 + + + + + + 1 + 1 + 0 0 0 + 0 + 0 + + + 1 + 0 + 0 + 1 + + 0 + + + + + 0 + 1e+06 + + + 0 + 1 + 1 + + 0 + 0.2 + 1e+13 + 1 + 0.01 + 0 + + + 1 + -0.01 + 0 + 0.2 + 1e+13 + 1 + + + + + + 1 + 1 + 0.143566 -1.4213 0 0 -0 0 + + + + + 1 + + 0.166667 + 0 + 0 + 0.166667 + 0 + 0.166667 + + 0 0 0 0 -0 0 + + 0 0 0 0 -0 0 + 1 + 0 + 0 + 0 + + -0.92725 1.7723 0 0 -0 0 + + + model://light_curtain/model/light_curtain.stl + 0.001 0.001 0.001 + + + 0 + 1 + + + 0 + 10 + -0.92725 1.7723 0 0 -0 0 + + + model://light_curtain/model/light_curtain.stl + 0.001 0.001 0.001 + + + + + + 1 + 1 + 0 0 0 + 0 + 0 + + + 1 + 0 + 0 + 1 + + 0 + + + + + 0 + 1e+06 + + + 0 + 1 + 1 + + 0 + 0.2 + 1e+13 + 1 + 0.01 + 0 + + + 1 + -0.01 + 0 + 0.2 + 1e+13 + 1 + + + + + + -0.605 0 0.22 0 -0 0 + + + + -0.001 + 0.001 + 640 + 1 + + + 1 + 0 + 0 + + + + 0.001 + 1.213 + + + + ir + link + link + infrared + + 1 + 10 + 1 + + + -0.605 0 0.32 0 -0 0 + + + + -0.001 + 0.001 + 640 + 1 + + + 1 + 0 + 0 + + + + 0.001 + 1.213 + 0.001 + + + + ir1 + link + link + infrared + + 1 + 10 + 1 + + + -0.605 0 0.42 0 -0 0 + + + + -0.001 + 0.001 + 640 + 1 + + + 1 + 0 + 0 + + + + 0.001 + 1.213 + 0.001 + + + + ir2 + link + link + infrared + + 1 + 10 + 1 + + + -0.605 0 0.52 0 -0 0 + + + + 320 + 1 + -0.001 + 0.001 + + + 1 + 0 + 0 + + + + 0.001 + 1.213 + 0.001 + + + + ir3 + link + link + infrared + + 1 + 10 + 1 + + + -0.605 0 0.62 0 -0 0 + + + + -0.001 + 0.001 + 640 + 1 + + + 1 + 0 + 0 + + + + 0.001 + 1.213 + 0.001 + + + + ir4 + link + link + infrared + + 1 + 10 + 1 + + + -0.605 0 0.72 0 -0 0 + + + + -0.001 + 0.001 + 640 + 1 + + + 1 + 0 + 0 + + + + 0.001 + 1.213 + 0.001 + + + + ir5 + link + link + infrared + + 1 + 10 + 1 + + + -0.605 0 0.82 0 -0 0 + + + + -0.001 + 0.001 + 640 + 1 + + + 1 + 0 + 0 + + + + 0.001 + 1.213 + 0.001 + + + + ir6 + link + link + infrared + + 1 + 10 + 1 + + + -0.605 0 0.92 0 -0 0 + + + + -0.001 + 0.001 + 640 + 1 + + + 1 + 0 + 0 + + + + 0.001 + 1.213 + 0.001 + + + + ir7 + link + link + infrared + + 1 + 10 + 1 + + + -0.605 0 1.02 0 -0 0 + + + + -0.001 + 0.001 + 640 + 1 + + + 1 + 0 + 0 + + + + 0.001 + 1.213 + 0.001 + + + + ir8 + link + link + infrared + + 1 + 10 + 1 + + + 1 + 1 + 2.80566 -1.32602 0 0 -0 0 + + + + + 1 + + 0.166667 + 0 + 0 + 0.166667 + 0 + 0.166667 + + 0 0 0 0 -0 0 + + 0 0 0 0 -0 0 + 1 + 0 + 0 + 0 + + 0.7 -3.7 0 0 -0 0 + + + model://kabinet/model/Kabinet.stl + 0.001 0.001 0.00125 + + + 0 + 1 + + + 0 + 10 + 0.7 3.7 0 0 -0 0 + + + model://kabinet/model/Kabinet.stl + 0.001 0.001 0.00125 + + + + + + 1 + 1 + 0 0 0 + 0 + 0 + + + 1 + 0 + 0 + 1 + + 0 + + + + + 0 + 1e+06 + + + 0 + 1 + 1 + + 0 + 0.2 + 1e+13 + 1 + 0.01 + 0 + + + 1 + -0.01 + 0 + 0.2 + 1e+13 + 1 + + + + + + 1 + 1 + -0.742257 -2.41133 0 0 0 -1.5708 + + + + + 1 + + 0.166667 + 0 + 0 + 0.166667 + 0 + 0.166667 + + 0 0 0 0 -0 0 + + 0 0 0 0 -0 0 + 1 + 0 + 0 + 0 + + 1.085 0.4 0 0 -0 0 + + + model://barrier/model/barrier.stl + 0.001 0.001 0.001 + + + 0 + 1 + + + 0 + 10 + 1.085 0.4 0 0 -0 0 + + + model://barrier/model/barrier.stl + 0.001 0.001 0.001 + + + + + + 1 + 1 + 0 0 0 + 0 + 0 + + + 1 + 0 + 0 + 1 + + 0 + + + + + 0 + 1e+06 + + + 0 + 1 + 1 + + 0 + 0.2 + 1e+13 + 1 + 0.01 + 0 + + + 1 + -0.01 + 0 + 0.2 + 1e+13 + 1 + + + + + + 1 + 1 + -0.36548 2.02914 0 0 -0 0 + + + + + 1 + + 0.166667 + 0 + 0 + 0.166667 + 0 + 0.166667 + + 0 0 0 0 -0 0 + + 0 0 0 0 -0 0 + 1 + 0 + 0 + 0 + + 1.085 0.4 0 0 -0 0 + + + model://barrier/model/barrier.stl + 0.001 0.001 0.001 + + + 0 + 1 + + + 0 + 10 + 1.085 0.4 0 0 -0 0 + + + model://barrier/model/barrier.stl + 0.001 0.001 0.001 + + + + + + 1 + 1 + 0 0 0 + 0 + 0 + + + 1 + 0 + 0 + 1 + + 0 + + + + + 0 + 1e+06 + + + 0 + 1 + 1 + + 0 + 0.2 + 1e+13 + 1 + 0.01 + 0 + + + 1 + -0.01 + 0 + 0.2 + 1e+13 + 1 + + + + + + 1 + 1 + 0.811401 2 0 0 -0 -3.14159 + + + + + 1 + + 0.166667 + 0 + 0 + 0.166667 + 0 + 0.166667 + + 0 0 0 0 -0 0 + + 0 0 0 0 -0 0 + 1 + 0 + 0 + 0 + + 1.085 0.4 0 0 -0 0 + + + model://barrier/model/barrier.stl + 0.001 0.001 0.001 + + + 0 + 1 + + + 0 + 10 + 1.085 0.4 0 0 -0 0 + + + model://barrier/model/barrier.stl + 0.001 0.001 0.001 + + + + + + 1 + 1 + 0 0 0 + 0 + 0 + + + 1 + 0 + 0 + 1 + + 0 + + + + + 0 + 1e+06 + + + 0 + 1 + 1 + + 0 + 0.2 + 1e+13 + 1 + 0.01 + 0 + + + 1 + -0.01 + 0 + 0.2 + 1e+13 + 1 + + + + + + 1 + 1 + 2 2 0 0 -0 -3.14159 + + + + + 1 + + 0.166667 + 0 + 0 + 0.166667 + 0 + 0.166667 + + 0 0 0 0 -0 0 + + 0 0 0 0 -0 0 + 1 + 0 + 0 + 0 + + 1.085 0.4 0 0 -0 0 + + + model://barrier/model/barrier.stl + 0.001 0.001 0.001 + + + 0 + 1 + + + 0 + 10 + 1.085 0.4 0 0 -0 0 + + + model://barrier/model/barrier.stl + 0.001 0.001 0.001 + + + + + + 1 + 1 + 0 0 0 + 0 + 0 + + + 1 + 0 + 0 + 1 + + 0 + + + + + 0 + 1e+06 + + + 0 + 1 + 1 + + 0 + 0.2 + 1e+13 + 1 + 0.01 + 0 + + + 1 + -0.01 + 0 + 0.2 + 1e+13 + 1 + + + + + + 1 + 1 + -0.404037 -1.95 0 0 -0 0 + + + + + 1 + + 0.166667 + 0 + 0 + 0.166667 + 0 + 0.166667 + + 0 0 0 0 -0 0 + + 0 0 0 0 -0 0 + 1 + 0 + 0 + 0 + + 1.085 0.4 0 0 -0 0 + + + model://barrier/model/barrier.stl + 0.001 0.001 0.001 + + + 0 + 1 + + + 0 + 10 + 1.085 0.4 0 0 -0 0 + + + model://barrier/model/barrier.stl + 0.001 0.001 0.001 + + + + + + 1 + 1 + 0 0 0 + 0 + 0 + + + 1 + 0 + 0 + 1 + + 0 + + + + + 0 + 1e+06 + + + 0 + 1 + 1 + + 0 + 0.2 + 1e+13 + 1 + 0.01 + 0 + + + 1 + -0.01 + 0 + 0.2 + 1e+13 + 1 + + + + + + 1 + 1 + -0.966612 1.34 0 0 0 -1.5708 + + + + + 1 + + 0.166667 + 0 + 0 + 0.166667 + 0 + 0.166667 + + 0 0 0 0 -0 0 + + 0 0 0 0 -0 0 + 1 + 0 + 0 + 0 + + 1.085 0.4 0 0 -0 0 + + + model://barrier/model/barrier.stl + 0.001 0.001 0.001 + + + 0 + 1 + + + 0 + 10 + 1.085 0.4 0 0 -0 0 + + + model://barrier/model/barrier.stl + 0.001 0.001 0.001 + + + + + + 1 + 1 + 0 0 0 + 0 + 0 + + + 1 + 0 + 0 + 1 + + 0 + + + + + 0 + 1e+06 + + + 0 + 1 + 1 + + 0 + 0.2 + 1e+13 + 1 + 0.01 + 0 + + + 1 + -0.01 + 0 + 0.2 + 1e+13 + 1 + + + + + + 1 + 1 + -0.95 0.04 0 0 0 -1.5708 + + + + + 1 + + 0.166667 + 0 + 0 + 0.166667 + 0 + 0.166667 + + 0 0 0 0 -0 0 + + 0 0 0 0 -0 0 + 1 + 0 + 0 + 0 + + 1.085 0.4 0 0 -0 0 + + + model://barrier/model/barrier.stl + 0.001 0.001 0.001 + + + 0 + 1 + + + 0 + 10 + 1.085 0.4 0 0 -0 0 + + + model://barrier/model/barrier.stl + 0.001 0.001 0.001 + + + + + + 1 + 1 + 0 0 0 + 0 + 0 + + + 1 + 0 + 0 + 1 + + 0 + + + + + 0 + 1e+06 + + + 0 + 1 + 1 + + 0 + 0.2 + 1e+13 + 1 + 0.01 + 0 + + + 1 + -0.01 + 0 + 0.2 + 1e+13 + 1 + + + + + + 1 + 1 + -0.947469 -1.26 0 0 0 -1.5708 + + + + + 1 + + 0.166667 + 0 + 0 + 0.166667 + 0 + 0.166667 + + 0 0 0 0 -0 0 + + 0 0 0 0 -0 0 + 1 + 0 + 0 + 0 + + 1.085 0.4 0 0 -0 0 + + + model://barrier/model/barrier.stl + 0.001 0.001 0.001 + + + 0 + 1 + + + 0 + 10 + 1.085 0.4 0 0 -0 0 + + + model://barrier/model/barrier.stl + 0.001 0.001 0.001 + + + + + + 1 + 1 + 0 0 0 + 0 + 0 + + + 1 + 0 + 0 + 1 + + 0 + + + + + 0 + 1e+06 + + + 0 + 1 + 1 + + 0 + 0.2 + 1e+13 + 1 + 0.01 + 0 + + + 1 + -0.01 + 0 + 0.2 + 1e+13 + 1 + + + + + + 1 + 1 + 2.5 -1.26 0 0 -0 1.5708 + + + + + 1 + + 0.166667 + 0 + 0 + 0.166667 + 0 + 0.166667 + + 0 0 0 0 -0 0 + + 0 0 0 0 -0 0 + 1 + 0 + 0 + 0 + + 1.085 0.4 0 0 -0 0 + + + model://barrier/model/barrier.stl + 0.001 0.001 0.001 + + + 0 + 1 + + + 0 + 10 + 1.085 0.4 0 0 -0 0 + + + model://barrier/model/barrier.stl + 0.001 0.001 0.001 + + + + + + 1 + 1 + 0 0 0 + 0 + 0 + + + 1 + 0 + 0 + 1 + + 0 + + + + + 0 + 1e+06 + + + 0 + 1 + 1 + + 0 + 0.2 + 1e+13 + 1 + 0.01 + 0 + + + 1 + -0.01 + 0 + 0.2 + 1e+13 + 1 + + + + + + 1 + 1 + 2.5 0.04 0 0 -0 1.5708 + + + + + 1 + + 0.166667 + 0 + 0 + 0.166667 + 0 + 0.166667 + + 0 0 0 0 -0 0 + + 0 0 0 0 -0 0 + 1 + 0 + 0 + 0 + + 1.085 0.4 0 0 -0 0 + + + model://barrier/model/barrier.stl + 0.001 0.001 0.001 + + + 0 + 1 + + + 0 + 10 + 1.085 0.4 0 0 -0 0 + + + model://barrier/model/barrier.stl + 0.001 0.001 0.001 + + + + + + 1 + 1 + 0 0 0 + 0 + 0 + + + 1 + 0 + 0 + 1 + + 0 + + + + + 0 + 1e+06 + + + 0 + 1 + 1 + + 0 + 0.2 + 1e+13 + 1 + 0.01 + 0 + + + 1 + -0.01 + 0 + 0.2 + 1e+13 + 1 + + + + + + 1 + 1 + 2.5 1.34 0 0 -0 1.5708 + + + + + 1 + + 0.166667 + 0 + 0 + 0.166667 + 0 + 0.166667 + + 0 0 0 0 -0 0 + + 0 0 0 0 -0 0 + 1 + 0 + 0 + 0 + + 1.085 0.4 0 0 -0 0 + + + model://barrier/model/barrier.stl + 0.001 0.001 0.001 + + + 0 + 1 + + + 0 + 10 + 1.085 0.4 0 0 -0 0 + + + model://barrier/model/barrier.stl + 0.001 0.001 0.001 + + + + + + 1 + 1 + 0 0 0 + 0 + 0 + + + 1 + 0 + 0 + 1 + + 0 + + + + + 0 + 1e+06 + + + 0 + 1 + 1 + + 0 + 0.2 + 1e+13 + 1 + 0.01 + 0 + + + 1 + -0.01 + 0 + 0.2 + 1e+13 + 1 + + + + + + 1 + 1 + 1.9807 -1.95 0 0 -0 0 + + + 4122 55000000 + 71 508182791 + 1671461308 533694518 + 59476 + + -0.388652 2 0 0 0 -3.14159 + 1 1 1 + + -0.388652 2 0 0 -0 -3.14159 + 0 0 0 0 -0 0 + 0 0 0 0 -0 0 + 0 0 0 0 -0 0 + + + + 0.811401 2 0 0 0 -3.14159 + 1 1 1 + + 0.811401 2 0 0 -0 -3.14159 + 0 0 0 0 -0 0 + 0 0 0 0 -0 0 + 0 0 0 0 -0 0 + + + + 2 2 0 0 0 -3.14159 + 1 1 1 + + 2 2 0 0 -0 -3.14159 + 0 0 0 0 -0 0 + 0 0 0 0 -0 0 + 0 0 0 0 -0 0 + + + + -0.404037 -1.95 0 0 -0 0 + 1 1 1 + + -0.404037 -1.95 0 0 -0 0 + 0 0 0 0 -0 0 + 0 0 0 0 -0 0 + 0 0 0 0 -0 0 + + + + -0.966612 1.34 0 0 0 -1.5708 + 1 1 1 + + -0.966612 1.34 0 0 0 -1.5708 + 0 0 0 0 -0 0 + 0 0 0 0 -0 0 + 0 0 0 0 -0 0 + + + + -0.95 0.04 0 0 0 -1.5708 + 1 1 1 + + -0.95 0.04 0 0 0 -1.5708 + 0 0 0 0 -0 0 + 0 0 0 0 -0 0 + 0 0 0 0 -0 0 + + + + -0.947469 -1.26 0 0 0 -1.5708 + 1 1 1 + + -0.947469 -1.26 0 0 0 -1.5708 + 0 0 0 0 -0 0 + 0 0 0 0 -0 0 + 0 0 0 0 -0 0 + + + + 2.5 -1.26 0 0 -0 1.5708 + 1 1 1 + + 2.5 -1.26 0 0 -0 1.5708 + 0 0 0 0 -0 0 + 0 0 0 0 -0 0 + 0 0 0 0 -0 0 + + + + 2.5 0.04 0 0 -0 1.5708 + 1 1 1 + + 2.5 0.04 0 0 -0 1.5708 + 0 0 0 0 -0 0 + 0 0 0 0 -0 0 + 0 0 0 0 -0 0 + + + + 2.5 1.34 0 0 -0 1.5708 + 1 1 1 + + 2.5 1.34 0 0 -0 1.5708 + 0 0 0 0 -0 0 + 0 0 0 0 -0 0 + 0 0 0 0 -0 0 + + + + 1.9807 -1.95 0 0 -0 0 + 1 1 1 + + 1.9807 -1.95 0 0 -0 0 + 0 0 0 0 -0 0 + 0 0 0 0 -0 0 + 0 0 0 0 -0 0 + + + + 0 0 0 0 -0 0 + 1 1 1 + + 0 0 0 0 -0 0 + 0 0 0 0 -0 0 + 0 0 0 0 -0 0 + 0 0 0 0 -0 0 + + + + 0.861944 0.675165 0 0 0 -1.5708 + 1 1 1 + + 0.861944 0.675165 0 0 0 -1.5708 + 0 0 0 0 -0 0 + 0 0 0 0 -0 0 + 0 0 0 0 -0 0 + + + + 0 0 0 0 -0 3.14159 + 1 1 1 + + 0 0 0 0 -0 3.14159 + 0 0 0 0 -0 0 + 0 0 0 0 -0 0 + 0 0 0 0 -0 0 + + + + -0.742257 -2.41133 0 0 0 -1.5708 + 1 1 1 + + -0.742257 -2.41133 0 0 0 -1.5708 + 0 0 0 0 -0 0 + 0 0 0 0 -0 0 + 0 0 0 0 -0 0 + + + + 0.78522 -2 0 0 -0 0 + 1 1 1 + + 0.78522 -2 0 0 -0 0 + 0 0 0 0 -0 0 + 0 0 0 0 -0 0 + 0 0 0 0 -0 0 + + + + 0 0 10 0 -0 0 + + + + + -11.1192 0.19141 6.61232 0 0.509791 -0.032615 + orbit + perspective + + + + + + 1 + + 0.166667 + 0 + 0 + 0.166667 + 0 + 0.166667 + + 0 0 0 0 -0 0 + + 0 0 0 0 -0 0 + 1 + 0 + 0 + 0 + + 0 0 0 0 -0 0 + + + model://ifarlab_bus/model/ifarlab_bus.stl + 0.001 0.001 0.001 + + + + 1 + 1 0 0 1 + 1 0 0 1 + 0.1 0.1 0.1 1 + 0 0 0 0 + + 0 + 1 + + + 0 + 10 + 0 0 0 0 -0 0 + + + model://ifarlab_bus/model/ifarlab_bus.stl + 0.001 0.001 0.001 + + + + + + 1 + 1 + 0 0 0 + 0 + 0 + + + 1 + 0 + 0 + 1 + + 0 + + + + + 0 + 1e+06 + + + 0 + 1 + 1 + + 0 + 0.2 + 1e+13 + 1 + 0.01 + 0 + + + 1 + -0.01 + 0 + 0.2 + 1e+13 + 1 + + + + + + 1 + 1 + 5.2637 0.395216 0 0 -0 0 + + + diff --git a/mobile_manipulator/mobile_manipulator_config_v1/world/ifarlab_value3s_v2.world b/mobile_manipulator/mobile_manipulator_config_v1/world/ifarlab_value3s_v2.world new file mode 100644 index 0000000..64480a3 --- /dev/null +++ b/mobile_manipulator/mobile_manipulator_config_v1/world/ifarlab_value3s_v2.world @@ -0,0 +1,1926 @@ + + + + 1 + 0 0 10 0 -0 0 + 0.8 0.8 0.8 1 + 0.2 0.2 0.2 1 + + 1000 + 0.9 + 0.01 + 0.001 + + -0.5 0.1 -0.9 + + 0 + 0 + 0 + + + + 1 + + + + + 0 0 1 + 100 100 + + + + + 65535 + + + + + 100 + 50 + + + + + + + + 10 + + + 0 + + + 0 0 1 + 100 100 + + + + + + + 0 + 0 + 0 + + + 0 0 -9.8 + 6e-06 2.3e-05 -4.2e-05 + + + 0.001 + 1 + 1000 + + + 0.4 0.4 0.4 1 + 0.7 0.7 0.7 1 + 1 + + + + EARTH_WGS84 + 0 + 0 + 0 + 0 + + + + + 1 + + 0.166667 + 0 + 0 + 0.166667 + 0 + 0.166667 + + 0 0 0 0 -0 0 + + 0 0 0 0 -0 0 + 1 + 0 + 0 + 0 + + 0.4 -1.28 0 0 -0 0 + + + model://ifarlab_ray/model/ifarlab_ray.stl + 0.001 0.001 0.001 + + + 0 + 1 + + + 0 + 10 + 0.4 -1.28 0 0 -0 0 + + + model://ifarlab_ray/model/ifarlab_ray.stl + 0.001 0.001 0.001 + + + + + + 1 + 1 + 0 0 0 + 0 + 0 + + + 1 + 0 + 0 + 1 + + 0 + + + + + 0 + 1e+06 + + + 0 + 1 + 1 + + 0 + 0.2 + 1e+13 + 1 + 0.01 + 0 + + + 1 + -0.01 + 0 + 0.2 + 1e+13 + 1 + + + + + + 1 + 1 + 0.143566 -1.4213 0 0 -0 0 + + + + + 1 + + 0.166667 + 0 + 0 + 0.166667 + 0 + 0.166667 + + 0 0 0 0 -0 0 + + 0 0 0 0 -0 0 + 1 + 0 + 0 + 0 + + -0.92725 1.7723 0 0 -0 0 + + + model://light_curtain/model/light_curtain.stl + 0.001 0.001 0.001 + + + 0 + 1 + + + 0 + 10 + -0.92725 1.7723 0 0 -0 0 + + + model://light_curtain/model/light_curtain.stl + 0.001 0.001 0.001 + + + + + + 1 + 1 + 0 0 0 + 0 + 0 + + + 1 + 0 + 0 + 1 + + 0 + + + + + 0 + 1e+06 + + + 0 + 1 + 1 + + 0 + 0.2 + 1e+13 + 1 + 0.01 + 0 + + + 1 + -0.01 + 0 + 0.2 + 1e+13 + 1 + + + + + + -0.605 0 0.22 0 -0 0 + + + + -0.001 + 0.001 + 640 + 1 + + + 1 + 0 + 0 + + + + 0.001 + 1.213 + + + + ir + link + link + infrared + + 1 + 10 + 1 + + + -0.605 0 0.32 0 -0 0 + + + + -0.001 + 0.001 + 640 + 1 + + + 1 + 0 + 0 + + + + 0.001 + 1.213 + 0.001 + + + + ir1 + link + link + infrared + + 1 + 10 + 1 + + + -0.605 0 0.42 0 -0 0 + + + + -0.001 + 0.001 + 640 + 1 + + + 1 + 0 + 0 + + + + 0.001 + 1.213 + 0.001 + + + + ir2 + link + link + infrared + + 1 + 10 + 1 + + + -0.605 0 0.52 0 -0 0 + + + + 320 + 1 + -0.001 + 0.001 + + + 1 + 0 + 0 + + + + 0.001 + 1.213 + 0.001 + + + + ir3 + link + link + infrared + + 1 + 10 + 1 + + + -0.605 0 0.62 0 -0 0 + + + + -0.001 + 0.001 + 640 + 1 + + + 1 + 0 + 0 + + + + 0.001 + 1.213 + 0.001 + + + + ir4 + link + link + infrared + + 1 + 10 + 1 + + + -0.605 0 0.72 0 -0 0 + + + + -0.001 + 0.001 + 640 + 1 + + + 1 + 0 + 0 + + + + 0.001 + 1.213 + 0.001 + + + + ir5 + link + link + infrared + + 1 + 10 + 1 + + + -0.605 0 0.82 0 -0 0 + + + + -0.001 + 0.001 + 640 + 1 + + + 1 + 0 + 0 + + + + 0.001 + 1.213 + 0.001 + + + + ir6 + link + link + infrared + + 1 + 10 + 1 + + + -0.605 0 0.92 0 -0 0 + + + + -0.001 + 0.001 + 640 + 1 + + + 1 + 0 + 0 + + + + 0.001 + 1.213 + 0.001 + + + + ir7 + link + link + infrared + + 1 + 10 + 1 + + + -0.605 0 1.02 0 -0 0 + + + + -0.001 + 0.001 + 640 + 1 + + + 1 + 0 + 0 + + + + 0.001 + 1.213 + 0.001 + + + + ir8 + link + link + infrared + + 1 + 10 + 1 + + + 1 + 1 + 2.80566 -1.32602 0 0 -0 0 + + + + + 1 + + 0.166667 + 0 + 0 + 0.166667 + 0 + 0.166667 + + 0 0 0 0 -0 0 + + 0 0 0 0 -0 0 + 1 + 0 + 0 + 0 + + 0.7 -3.7 0 0 -0 0 + + + model://kabinet/model/Kabinet.stl + 0.001 0.001 0.00125 + + + 0 + 1 + + + 0 + 10 + 0.7 3.7 0 0 -0 0 + + + model://kabinet/model/Kabinet.stl + 0.001 0.001 0.00125 + + + + + + 1 + 1 + 0 0 0 + 0 + 0 + + + 1 + 0 + 0 + 1 + + 0 + + + + + 0 + 1e+06 + + + 0 + 1 + 1 + + 0 + 0.2 + 1e+13 + 1 + 0.01 + 0 + + + 1 + -0.01 + 0 + 0.2 + 1e+13 + 1 + + + + + + 1 + 1 + -0.742257 -2.41133 0 0 0 -1.5708 + + + + + 1 + + 0.166667 + 0 + 0 + 0.166667 + 0 + 0.166667 + + 0 0 0 0 -0 0 + + 0 0 0 0 -0 0 + 1 + 0 + 0 + 0 + + 1.085 0.4 0 0 -0 0 + + + model://barrier/model/barrier.stl + 0.001 0.001 0.001 + + + 0 + 1 + + + 0 + 10 + 1.085 0.4 0 0 -0 0 + + + model://barrier/model/barrier.stl + 0.001 0.001 0.001 + + + + + + 1 + 1 + 0 0 0 + 0 + 0 + + + 1 + 0 + 0 + 1 + + 0 + + + + + 0 + 1e+06 + + + 0 + 1 + 1 + + 0 + 0.2 + 1e+13 + 1 + 0.01 + 0 + + + 1 + -0.01 + 0 + 0.2 + 1e+13 + 1 + + + + + + 1 + 1 + -0.36548 2.02914 0 0 -0 0 + + + + + 1 + + 0.166667 + 0 + 0 + 0.166667 + 0 + 0.166667 + + 0 0 0 0 -0 0 + + 0 0 0 0 -0 0 + 1 + 0 + 0 + 0 + + 1.085 0.4 0 0 -0 0 + + + model://barrier/model/barrier.stl + 0.001 0.001 0.001 + + + 0 + 1 + + + 0 + 10 + 1.085 0.4 0 0 -0 0 + + + model://barrier/model/barrier.stl + 0.001 0.001 0.001 + + + + + + 1 + 1 + 0 0 0 + 0 + 0 + + + 1 + 0 + 0 + 1 + + 0 + + + + + 0 + 1e+06 + + + 0 + 1 + 1 + + 0 + 0.2 + 1e+13 + 1 + 0.01 + 0 + + + 1 + -0.01 + 0 + 0.2 + 1e+13 + 1 + + + + + + 1 + 1 + 0.811401 2 0 0 -0 -3.14159 + + + + + 1 + + 0.166667 + 0 + 0 + 0.166667 + 0 + 0.166667 + + 0 0 0 0 -0 0 + + 0 0 0 0 -0 0 + 1 + 0 + 0 + 0 + + 1.085 0.4 0 0 -0 0 + + + model://barrier/model/barrier.stl + 0.001 0.001 0.001 + + + 0 + 1 + + + 0 + 10 + 1.085 0.4 0 0 -0 0 + + + model://barrier/model/barrier.stl + 0.001 0.001 0.001 + + + + + + 1 + 1 + 0 0 0 + 0 + 0 + + + 1 + 0 + 0 + 1 + + 0 + + + + + 0 + 1e+06 + + + 0 + 1 + 1 + + 0 + 0.2 + 1e+13 + 1 + 0.01 + 0 + + + 1 + -0.01 + 0 + 0.2 + 1e+13 + 1 + + + + + + 1 + 1 + 2 2 0 0 -0 -3.14159 + + + + + 1 + + 0.166667 + 0 + 0 + 0.166667 + 0 + 0.166667 + + 0 0 0 0 -0 0 + + 0 0 0 0 -0 0 + 1 + 0 + 0 + 0 + + 1.085 0.4 0 0 -0 0 + + + model://barrier/model/barrier.stl + 0.001 0.001 0.001 + + + 0 + 1 + + + 0 + 10 + 1.085 0.4 0 0 -0 0 + + + model://barrier/model/barrier.stl + 0.001 0.001 0.001 + + + + + + 1 + 1 + 0 0 0 + 0 + 0 + + + 1 + 0 + 0 + 1 + + 0 + + + + + 0 + 1e+06 + + + 0 + 1 + 1 + + 0 + 0.2 + 1e+13 + 1 + 0.01 + 0 + + + 1 + -0.01 + 0 + 0.2 + 1e+13 + 1 + + + + + + 1 + 1 + -0.404037 -1.95 0 0 -0 0 + + + + + 1 + + 0.166667 + 0 + 0 + 0.166667 + 0 + 0.166667 + + 0 0 0 0 -0 0 + + 0 0 0 0 -0 0 + 1 + 0 + 0 + 0 + + 1.085 0.4 0 0 -0 0 + + + model://barrier/model/barrier.stl + 0.001 0.001 0.001 + + + 0 + 1 + + + 0 + 10 + 1.085 0.4 0 0 -0 0 + + + model://barrier/model/barrier.stl + 0.001 0.001 0.001 + + + + + + 1 + 1 + 0 0 0 + 0 + 0 + + + 1 + 0 + 0 + 1 + + 0 + + + + + 0 + 1e+06 + + + 0 + 1 + 1 + + 0 + 0.2 + 1e+13 + 1 + 0.01 + 0 + + + 1 + -0.01 + 0 + 0.2 + 1e+13 + 1 + + + + + + 1 + 1 + -0.966612 1.34 0 0 0 -1.5708 + + + + + 1 + + 0.166667 + 0 + 0 + 0.166667 + 0 + 0.166667 + + 0 0 0 0 -0 0 + + 0 0 0 0 -0 0 + 1 + 0 + 0 + 0 + + 1.085 0.4 0 0 -0 0 + + + model://barrier/model/barrier.stl + 0.001 0.001 0.001 + + + 0 + 1 + + + 0 + 10 + 1.085 0.4 0 0 -0 0 + + + model://barrier/model/barrier.stl + 0.001 0.001 0.001 + + + + + + 1 + 1 + 0 0 0 + 0 + 0 + + + 1 + 0 + 0 + 1 + + 0 + + + + + 0 + 1e+06 + + + 0 + 1 + 1 + + 0 + 0.2 + 1e+13 + 1 + 0.01 + 0 + + + 1 + -0.01 + 0 + 0.2 + 1e+13 + 1 + + + + + + 1 + 1 + -0.95 0.04 0 0 0 -1.5708 + + + + + 1 + + 0.166667 + 0 + 0 + 0.166667 + 0 + 0.166667 + + 0 0 0 0 -0 0 + + 0 0 0 0 -0 0 + 1 + 0 + 0 + 0 + + 1.085 0.4 0 0 -0 0 + + + model://barrier/model/barrier.stl + 0.001 0.001 0.001 + + + 0 + 1 + + + 0 + 10 + 1.085 0.4 0 0 -0 0 + + + model://barrier/model/barrier.stl + 0.001 0.001 0.001 + + + + + + 1 + 1 + 0 0 0 + 0 + 0 + + + 1 + 0 + 0 + 1 + + 0 + + + + + 0 + 1e+06 + + + 0 + 1 + 1 + + 0 + 0.2 + 1e+13 + 1 + 0.01 + 0 + + + 1 + -0.01 + 0 + 0.2 + 1e+13 + 1 + + + + + + 1 + 1 + -0.947469 -1.26 0 0 0 -1.5708 + + + + + 1 + + 0.166667 + 0 + 0 + 0.166667 + 0 + 0.166667 + + 0 0 0 0 -0 0 + + 0 0 0 0 -0 0 + 1 + 0 + 0 + 0 + + 1.085 0.4 0 0 -0 0 + + + model://barrier/model/barrier.stl + 0.001 0.001 0.001 + + + 0 + 1 + + + 0 + 10 + 1.085 0.4 0 0 -0 0 + + + model://barrier/model/barrier.stl + 0.001 0.001 0.001 + + + + + + 1 + 1 + 0 0 0 + 0 + 0 + + + 1 + 0 + 0 + 1 + + 0 + + + + + 0 + 1e+06 + + + 0 + 1 + 1 + + 0 + 0.2 + 1e+13 + 1 + 0.01 + 0 + + + 1 + -0.01 + 0 + 0.2 + 1e+13 + 1 + + + + + + 1 + 1 + 2.5 -1.26 0 0 -0 1.5708 + + + + + 1 + + 0.166667 + 0 + 0 + 0.166667 + 0 + 0.166667 + + 0 0 0 0 -0 0 + + 0 0 0 0 -0 0 + 1 + 0 + 0 + 0 + + 1.085 0.4 0 0 -0 0 + + + model://barrier/model/barrier.stl + 0.001 0.001 0.001 + + + 0 + 1 + + + 0 + 10 + 1.085 0.4 0 0 -0 0 + + + model://barrier/model/barrier.stl + 0.001 0.001 0.001 + + + + + + 1 + 1 + 0 0 0 + 0 + 0 + + + 1 + 0 + 0 + 1 + + 0 + + + + + 0 + 1e+06 + + + 0 + 1 + 1 + + 0 + 0.2 + 1e+13 + 1 + 0.01 + 0 + + + 1 + -0.01 + 0 + 0.2 + 1e+13 + 1 + + + + + + 1 + 1 + 2.5 0.04 0 0 -0 1.5708 + + + + + 1 + + 0.166667 + 0 + 0 + 0.166667 + 0 + 0.166667 + + 0 0 0 0 -0 0 + + 0 0 0 0 -0 0 + 1 + 0 + 0 + 0 + + 1.085 0.4 0 0 -0 0 + + + model://barrier/model/barrier.stl + 0.001 0.001 0.001 + + + 0 + 1 + + + 0 + 10 + 1.085 0.4 0 0 -0 0 + + + model://barrier/model/barrier.stl + 0.001 0.001 0.001 + + + + + + 1 + 1 + 0 0 0 + 0 + 0 + + + 1 + 0 + 0 + 1 + + 0 + + + + + 0 + 1e+06 + + + 0 + 1 + 1 + + 0 + 0.2 + 1e+13 + 1 + 0.01 + 0 + + + 1 + -0.01 + 0 + 0.2 + 1e+13 + 1 + + + + + + 1 + 1 + 2.5 1.34 0 0 -0 1.5708 + + + + + 1 + + 0.166667 + 0 + 0 + 0.166667 + 0 + 0.166667 + + 0 0 0 0 -0 0 + + 0 0 0 0 -0 0 + 1 + 0 + 0 + 0 + + 1.085 0.4 0 0 -0 0 + + + model://barrier/model/barrier.stl + 0.001 0.001 0.001 + + + 0 + 1 + + + 0 + 10 + 1.085 0.4 0 0 -0 0 + + + model://barrier/model/barrier.stl + 0.001 0.001 0.001 + + + + + + 1 + 1 + 0 0 0 + 0 + 0 + + + 1 + 0 + 0 + 1 + + 0 + + + + + 0 + 1e+06 + + + 0 + 1 + 1 + + 0 + 0.2 + 1e+13 + 1 + 0.01 + 0 + + + 1 + -0.01 + 0 + 0.2 + 1e+13 + 1 + + + + + + 1 + 1 + 1.9807 -1.95 0 0 -0 0 + + + 4761 117000000 + 806 210874970 + 1672067803 917906315 + 639062 + + 2 0.388652 0 0 -0 1.5708 + 1 1 1 + + 2 0.388652 0 0 -0 1.5708 + 0 0 0 0 -0 0 + 0 0 0 0 -0 0 + 0 0 0 0 -0 0 + + + + 2 -0.811401 0 0 -0 1.5708 + 1 1 1 + + 2 -0.811401 0 0 -0 1.5708 + 0 0 0 0 -0 0 + 0 0 0 0 -0 0 + 0 0 0 0 -0 0 + + + + 2 -2 0 0 -0 1.5708 + 1 1 1 + + 2 -2 0 0 -0 1.5708 + 0 0 0 0 -0 0 + 0 0 0 0 -0 0 + 0 0 0 0 -0 0 + + + + -1.95 0.404037 0 0 0 -1.5708 + 1 1 1 + + -1.95 0.404037 0 0 0 -1.5708 + 0 0 0 0 -0 0 + 0 0 0 0 -0 0 + 0 0 0 0 -0 0 + + + + 1.34 0.95 0 0 -0 3.14159 + 1 1 1 + + 1.34 0.95 0 0 -0 3.14159 + 0 0 0 0 -0 0 + 0 0 0 0 -0 0 + 0 0 0 0 -0 0 + + + + 0.04 0.95 0 0 -0 3.14159 + 1 1 1 + + 0.04 0.95 0 0 -0 3.14159 + 0 0 0 0 -0 0 + 0 0 0 0 -0 0 + 0 0 0 0 -0 0 + + + + -1.26 0.947469 0 0 -0 3.14158 + 1 1 1 + + -1.26 0.947469 0 0 -0 3.14158 + 0 0 0 0 -0 0 + 0 0 0 0 -0 0 + 0 0 0 0 -0 0 + + + + -1.26 -2.5 0 0 -0 0 + 1 1 1 + + -1.26 -2.5 0 0 -0 0 + 0 0 0 0 -0 0 + 0 0 0 0 -0 0 + 0 0 0 0 -0 0 + + + + 0.04 -2.5 0 0 0.04 0 + 1 1 1 + + 0.04 -2.5 0 0 0.04 0 + 0 0 0 0 -0 0 + 0 0 0 0 -0 0 + 0 0 0 0 -0 0 + + + + 1.34 -2.5 0 0 -0 0 + 1 1 1 + + 1.34 -2.5 0 0 -0 0 + 0 0 0 0 -0 0 + 0 0 0 0 -0 0 + 0 0 0 0 -0 0 + + + + -1.95 -1.9807 0 0 0 -1.5708 + 1 1 1 + + -1.95 -1.9807 0 0 0 -1.5708 + 0 0 0 0 -0 0 + 0 0 0 0 -0 0 + 0 0 0 0 -0 0 + + + + 0 0 0 0 -0 0 + 1 1 1 + + 0 0 0 0 -0 0 + 0 0 0 0 -0 0 + 0 0 0 0 -0 0 + 0 0 0 0 -0 0 + + + + 0.675165 -0.861944 0 0 -0 3.14159 + 1 1 1 + + 0.675165 -0.861944 0 0 -0 3.14159 + 0 0 0 0 -0 0 + 0 0 0 0 -0 0 + 0 0 0 0 -0 0 + + + + 0 0 0 0 -0 1.5708 + 1 1 1 + + 0 0 0 0 -0 1.5708 + 0 0 0 0 -0 0 + 0 0 0 0 -0 0 + 0 0 0 0 -0 0 + + + + -2.41133 0.742257 0 0 -0 3.14159 + 1 1 1 + + -2.41133 0.742257 0 0 -0 3.14159 + 0 0 0 0 -0 0 + 0 0 0 0 -0 0 + 0 0 0 0 -0 0 + + + + -2 -0.78522 0 0 0 -1.5708 + 1 1 1 + + -2 -0.78522 0 0 0 -1.5708 + 0 0 0 0 -0 0 + 0 0 0 0 -0 0 + 0 0 0 0 -0 0 + + + + 0 0 10 0 -0 0 + + + + + 1.67844 10.4731 12.9116 0 0.80979 -1.54624 + orbit + perspective + + + + + + 1 + + 0.166667 + 0 + 0 + 0.166667 + 0 + 0.166667 + + 0 0 0 0 -0 0 + + 0 0 0 0 -0 0 + 1 + 0 + 0 + 0 + + 0 0 0 0 -0 0 + + + model://ifarlab_bus/model/ifarlab_bus.stl + 0.001 0.001 0.001 + + + + 1 + 1 0 0 1 + 1 0 0 1 + 0.1 0.1 0.1 1 + 0 0 0 0 + + 0 + 1 + + + 0 + 10 + 0 0 0 0 -0 0 + + + model://ifarlab_bus/model/ifarlab_bus.stl + 0.001 0.001 0.001 + + + + + + 1 + 1 + 0 0 0 + 0 + 0 + + + 1 + 0 + 0 + 1 + + 0 + + + + + 0 + 1e+06 + + + 0 + 1 + 1 + + 0 + 0.2 + 1e+13 + 1 + 0.01 + 0 + + + 1 + -0.01 + 0 + 0.2 + 1e+13 + 1 + + + + + + 1 + 1 + 5.2637 0.395216 0 0 -0 0 + + + diff --git a/mobile_manipulator/mobile_manipulator_config_v1/world/ifarlab_value3s_v3.world b/mobile_manipulator/mobile_manipulator_config_v1/world/ifarlab_value3s_v3.world new file mode 100644 index 0000000..eb98b9f --- /dev/null +++ b/mobile_manipulator/mobile_manipulator_config_v1/world/ifarlab_value3s_v3.world @@ -0,0 +1,1926 @@ + + + + 1 + 0 0 10 0 -0 0 + 0.8 0.8 0.8 1 + 0.2 0.2 0.2 1 + + 1000 + 0.9 + 0.01 + 0.001 + + -0.5 0.1 -0.9 + + 0 + 0 + 0 + + + + 1 + + + + + 0 0 1 + 100 100 + + + + + 65535 + + + + + 100 + 50 + + + + + + + + 10 + + + 0 + + + 0 0 1 + 100 100 + + + + + + + 0 + 0 + 0 + + + 0 0 -9.8 + 6e-06 2.3e-05 -4.2e-05 + + + 0.001 + 1 + 1000 + + + 0.4 0.4 0.4 1 + 0.7 0.7 0.7 1 + 1 + + + + EARTH_WGS84 + 0 + 0 + 0 + 0 + + + + + 1 + + 0.166667 + 0 + 0 + 0.166667 + 0 + 0.166667 + + 0 0 0 0 -0 0 + + 0 0 0 0 -0 0 + 1 + 0 + 0 + 0 + + 0.4 -1.28 0 0 -0 0 + + + model://ifarlab_ray/model/ifarlab_ray.stl + 0.001 0.001 0.001 + + + 0 + 1 + + + 0 + 10 + 0.4 -1.28 0 0 -0 0 + + + model://ifarlab_ray/model/ifarlab_ray.stl + 0.001 0.001 0.001 + + + + + + 1 + 1 + 0 0 0 + 0 + 0 + + + 1 + 0 + 0 + 1 + + 0 + + + + + 0 + 1e+06 + + + 0 + 1 + 1 + + 0 + 0.2 + 1e+13 + 1 + 0.01 + 0 + + + 1 + -0.01 + 0 + 0.2 + 1e+13 + 1 + + + + + + 1 + 1 + 1.28 -0 0 0 -0 0 + + + + + 1 + + 0.166667 + 0 + 0 + 0.166667 + 0 + 0.166667 + + 0 0 0 0 -0 0 + + 0 0 0 0 -0 0 + 1 + 0 + 0 + 0 + + -0.92725 1.7723 0 0 -0 0 + + + model://light_curtain/model/light_curtain.stl + 0.001 0.001 0.001 + + + 0 + 1 + + + 0 + 10 + -0.92725 1.7723 0 0 -0 0 + + + model://light_curtain/model/light_curtain.stl + 0.001 0.001 0.001 + + + + + + 1 + 1 + 0 0 0 + 0 + 0 + + + 1 + 0 + 0 + 1 + + 0 + + + + + 0 + 1e+06 + + + 0 + 1 + 1 + + 0 + 0.2 + 1e+13 + 1 + 0.01 + 0 + + + 1 + -0.01 + 0 + 0.2 + 1e+13 + 1 + + + + + + -0.605 0 0.22 0 -0 0 + + + + -0.001 + 0.001 + 640 + 1 + + + 1 + 0 + 0 + + + + 0.001 + 1.213 + + + + ir + link + link + infrared + + 1 + 10 + 1 + + + -0.605 0 0.32 0 -0 0 + + + + -0.001 + 0.001 + 640 + 1 + + + 1 + 0 + 0 + + + + 0.001 + 1.213 + 0.001 + + + + ir1 + link + link + infrared + + 1 + 10 + 1 + + + -0.605 0 0.42 0 -0 0 + + + + -0.001 + 0.001 + 640 + 1 + + + 1 + 0 + 0 + + + + 0.001 + 1.213 + 0.001 + + + + ir2 + link + link + infrared + + 1 + 10 + 1 + + + -0.605 0 0.52 0 -0 0 + + + + 320 + 1 + -0.001 + 0.001 + + + 1 + 0 + 0 + + + + 0.001 + 1.213 + 0.001 + + + + ir3 + link + link + infrared + + 1 + 10 + 1 + + + -0.605 0 0.62 0 -0 0 + + + + -0.001 + 0.001 + 640 + 1 + + + 1 + 0 + 0 + + + + 0.001 + 1.213 + 0.001 + + + + ir4 + link + link + infrared + + 1 + 10 + 1 + + + -0.605 0 0.72 0 -0 0 + + + + -0.001 + 0.001 + 640 + 1 + + + 1 + 0 + 0 + + + + 0.001 + 1.213 + 0.001 + + + + ir5 + link + link + infrared + + 1 + 10 + 1 + + + -0.605 0 0.82 0 -0 0 + + + + -0.001 + 0.001 + 640 + 1 + + + 1 + 0 + 0 + + + + 0.001 + 1.213 + 0.001 + + + + ir6 + link + link + infrared + + 1 + 10 + 1 + + + -0.605 0 0.92 0 -0 0 + + + + -0.001 + 0.001 + 640 + 1 + + + 1 + 0 + 0 + + + + 0.001 + 1.213 + 0.001 + + + + ir7 + link + link + infrared + + 1 + 10 + 1 + + + -0.605 0 1.02 0 -0 0 + + + + -0.001 + 0.001 + 640 + 1 + + + 1 + 0 + 0 + + + + 0.001 + 1.213 + 0.001 + + + + ir8 + link + link + infrared + + 1 + 10 + 1 + + + 1 + 1 + 2.80566 -1.32602 0 0 -0 0 + + + + + 1 + + 0.166667 + 0 + 0 + 0.166667 + 0 + 0.166667 + + 0 0 0 0 -0 0 + + 0 0 0 0 -0 0 + 1 + 0 + 0 + 0 + + 0.7 -3.7 0 0 -0 0 + + + model://kabinet/model/Kabinet.stl + 0.001 0.001 0.00125 + + + 0 + 1 + + + 0 + 10 + 0.7 3.7 0 0 -0 0 + + + model://kabinet/model/Kabinet.stl + 0.001 0.001 0.00125 + + + + + + 1 + 1 + 0 0 0 + 0 + 0 + + + 1 + 0 + 0 + 1 + + 0 + + + + + 0 + 1e+06 + + + 0 + 1 + 1 + + 0 + 0.2 + 1e+13 + 1 + 0.01 + 0 + + + 1 + -0.01 + 0 + 0.2 + 1e+13 + 1 + + + + + + 1 + 1 + -0.742257 -2.41133 0 0 0 -1.5708 + + + + + 1 + + 0.166667 + 0 + 0 + 0.166667 + 0 + 0.166667 + + 0 0 0 0 -0 0 + + 0 0 0 0 -0 0 + 1 + 0 + 0 + 0 + + 1.085 0.4 0 0 -0 0 + + + model://barrier/model/barrier.stl + 0.001 0.001 0.001 + + + 0 + 1 + + + 0 + 10 + 1.085 0.4 0 0 -0 0 + + + model://barrier/model/barrier.stl + 0.001 0.001 0.001 + + + + + + 1 + 1 + 0 0 0 + 0 + 0 + + + 1 + 0 + 0 + 1 + + 0 + + + + + 0 + 1e+06 + + + 0 + 1 + 1 + + 0 + 0.2 + 1e+13 + 1 + 0.01 + 0 + + + 1 + -0.01 + 0 + 0.2 + 1e+13 + 1 + + + + + + 1 + 1 + -0.36548 2.02914 0 0 -0 0 + + + + + 1 + + 0.166667 + 0 + 0 + 0.166667 + 0 + 0.166667 + + 0 0 0 0 -0 0 + + 0 0 0 0 -0 0 + 1 + 0 + 0 + 0 + + 1.085 0.4 0 0 -0 0 + + + model://barrier/model/barrier.stl + 0.001 0.001 0.001 + + + 0 + 1 + + + 0 + 10 + 1.085 0.4 0 0 -0 0 + + + model://barrier/model/barrier.stl + 0.001 0.001 0.001 + + + + + + 1 + 1 + 0 0 0 + 0 + 0 + + + 1 + 0 + 0 + 1 + + 0 + + + + + 0 + 1e+06 + + + 0 + 1 + 1 + + 0 + 0.2 + 1e+13 + 1 + 0.01 + 0 + + + 1 + -0.01 + 0 + 0.2 + 1e+13 + 1 + + + + + + 1 + 1 + 0.811401 2 0 0 -0 -3.14159 + + + + + 1 + + 0.166667 + 0 + 0 + 0.166667 + 0 + 0.166667 + + 0 0 0 0 -0 0 + + 0 0 0 0 -0 0 + 1 + 0 + 0 + 0 + + 1.085 0.4 0 0 -0 0 + + + model://barrier/model/barrier.stl + 0.001 0.001 0.001 + + + 0 + 1 + + + 0 + 10 + 1.085 0.4 0 0 -0 0 + + + model://barrier/model/barrier.stl + 0.001 0.001 0.001 + + + + + + 1 + 1 + 0 0 0 + 0 + 0 + + + 1 + 0 + 0 + 1 + + 0 + + + + + 0 + 1e+06 + + + 0 + 1 + 1 + + 0 + 0.2 + 1e+13 + 1 + 0.01 + 0 + + + 1 + -0.01 + 0 + 0.2 + 1e+13 + 1 + + + + + + 1 + 1 + 2 2 0 0 -0 -3.14159 + + + + + 1 + + 0.166667 + 0 + 0 + 0.166667 + 0 + 0.166667 + + 0 0 0 0 -0 0 + + 0 0 0 0 -0 0 + 1 + 0 + 0 + 0 + + 1.085 0.4 0 0 -0 0 + + + model://barrier/model/barrier.stl + 0.001 0.001 0.001 + + + 0 + 1 + + + 0 + 10 + 1.085 0.4 0 0 -0 0 + + + model://barrier/model/barrier.stl + 0.001 0.001 0.001 + + + + + + 1 + 1 + 0 0 0 + 0 + 0 + + + 1 + 0 + 0 + 1 + + 0 + + + + + 0 + 1e+06 + + + 0 + 1 + 1 + + 0 + 0.2 + 1e+13 + 1 + 0.01 + 0 + + + 1 + -0.01 + 0 + 0.2 + 1e+13 + 1 + + + + + + 1 + 1 + -0.404037 -1.95 0 0 -0 0 + + + + + 1 + + 0.166667 + 0 + 0 + 0.166667 + 0 + 0.166667 + + 0 0 0 0 -0 0 + + 0 0 0 0 -0 0 + 1 + 0 + 0 + 0 + + 1.085 0.4 0 0 -0 0 + + + model://barrier/model/barrier.stl + 0.001 0.001 0.001 + + + 0 + 1 + + + 0 + 10 + 1.085 0.4 0 0 -0 0 + + + model://barrier/model/barrier.stl + 0.001 0.001 0.001 + + + + + + 1 + 1 + 0 0 0 + 0 + 0 + + + 1 + 0 + 0 + 1 + + 0 + + + + + 0 + 1e+06 + + + 0 + 1 + 1 + + 0 + 0.2 + 1e+13 + 1 + 0.01 + 0 + + + 1 + -0.01 + 0 + 0.2 + 1e+13 + 1 + + + + + + 1 + 1 + -0.966612 1.34 0 0 0 -1.5708 + + + + + 1 + + 0.166667 + 0 + 0 + 0.166667 + 0 + 0.166667 + + 0 0 0 0 -0 0 + + 0 0 0 0 -0 0 + 1 + 0 + 0 + 0 + + 1.085 0.4 0 0 -0 0 + + + model://barrier/model/barrier.stl + 0.001 0.001 0.001 + + + 0 + 1 + + + 0 + 10 + 1.085 0.4 0 0 -0 0 + + + model://barrier/model/barrier.stl + 0.001 0.001 0.001 + + + + + + 1 + 1 + 0 0 0 + 0 + 0 + + + 1 + 0 + 0 + 1 + + 0 + + + + + 0 + 1e+06 + + + 0 + 1 + 1 + + 0 + 0.2 + 1e+13 + 1 + 0.01 + 0 + + + 1 + -0.01 + 0 + 0.2 + 1e+13 + 1 + + + + + + 1 + 1 + -0.95 0.04 0 0 0 -1.5708 + + + + + 1 + + 0.166667 + 0 + 0 + 0.166667 + 0 + 0.166667 + + 0 0 0 0 -0 0 + + 0 0 0 0 -0 0 + 1 + 0 + 0 + 0 + + 1.085 0.4 0 0 -0 0 + + + model://barrier/model/barrier.stl + 0.001 0.001 0.001 + + + 0 + 1 + + + 0 + 10 + 1.085 0.4 0 0 -0 0 + + + model://barrier/model/barrier.stl + 0.001 0.001 0.001 + + + + + + 1 + 1 + 0 0 0 + 0 + 0 + + + 1 + 0 + 0 + 1 + + 0 + + + + + 0 + 1e+06 + + + 0 + 1 + 1 + + 0 + 0.2 + 1e+13 + 1 + 0.01 + 0 + + + 1 + -0.01 + 0 + 0.2 + 1e+13 + 1 + + + + + + 1 + 1 + -0.947469 -1.26 0 0 0 -1.5708 + + + + + 1 + + 0.166667 + 0 + 0 + 0.166667 + 0 + 0.166667 + + 0 0 0 0 -0 0 + + 0 0 0 0 -0 0 + 1 + 0 + 0 + 0 + + 1.085 0.4 0 0 -0 0 + + + model://barrier/model/barrier.stl + 0.001 0.001 0.001 + + + 0 + 1 + + + 0 + 10 + 1.085 0.4 0 0 -0 0 + + + model://barrier/model/barrier.stl + 0.001 0.001 0.001 + + + + + + 1 + 1 + 0 0 0 + 0 + 0 + + + 1 + 0 + 0 + 1 + + 0 + + + + + 0 + 1e+06 + + + 0 + 1 + 1 + + 0 + 0.2 + 1e+13 + 1 + 0.01 + 0 + + + 1 + -0.01 + 0 + 0.2 + 1e+13 + 1 + + + + + + 1 + 1 + 2.5 -1.26 0 0 -0 1.5708 + + + + + 1 + + 0.166667 + 0 + 0 + 0.166667 + 0 + 0.166667 + + 0 0 0 0 -0 0 + + 0 0 0 0 -0 0 + 1 + 0 + 0 + 0 + + 1.085 0.4 0 0 -0 0 + + + model://barrier/model/barrier.stl + 0.001 0.001 0.001 + + + 0 + 1 + + + 0 + 10 + 1.085 0.4 0 0 -0 0 + + + model://barrier/model/barrier.stl + 0.001 0.001 0.001 + + + + + + 1 + 1 + 0 0 0 + 0 + 0 + + + 1 + 0 + 0 + 1 + + 0 + + + + + 0 + 1e+06 + + + 0 + 1 + 1 + + 0 + 0.2 + 1e+13 + 1 + 0.01 + 0 + + + 1 + -0.01 + 0 + 0.2 + 1e+13 + 1 + + + + + + 1 + 1 + 2.5 0.04 0 0 -0 1.5708 + + + + + 1 + + 0.166667 + 0 + 0 + 0.166667 + 0 + 0.166667 + + 0 0 0 0 -0 0 + + 0 0 0 0 -0 0 + 1 + 0 + 0 + 0 + + 1.085 0.4 0 0 -0 0 + + + model://barrier/model/barrier.stl + 0.001 0.001 0.001 + + + 0 + 1 + + + 0 + 10 + 1.085 0.4 0 0 -0 0 + + + model://barrier/model/barrier.stl + 0.001 0.001 0.001 + + + + + + 1 + 1 + 0 0 0 + 0 + 0 + + + 1 + 0 + 0 + 1 + + 0 + + + + + 0 + 1e+06 + + + 0 + 1 + 1 + + 0 + 0.2 + 1e+13 + 1 + 0.01 + 0 + + + 1 + -0.01 + 0 + 0.2 + 1e+13 + 1 + + + + + + 1 + 1 + 2.5 1.34 0 0 -0 1.5708 + + + + + 1 + + 0.166667 + 0 + 0 + 0.166667 + 0 + 0.166667 + + 0 0 0 0 -0 0 + + 0 0 0 0 -0 0 + 1 + 0 + 0 + 0 + + 1.085 0.4 0 0 -0 0 + + + model://barrier/model/barrier.stl + 0.001 0.001 0.001 + + + 0 + 1 + + + 0 + 10 + 1.085 0.4 0 0 -0 0 + + + model://barrier/model/barrier.stl + 0.001 0.001 0.001 + + + + + + 1 + 1 + 0 0 0 + 0 + 0 + + + 1 + 0 + 0 + 1 + + 0 + + + + + 0 + 1e+06 + + + 0 + 1 + 1 + + 0 + 0.2 + 1e+13 + 1 + 0.01 + 0 + + + 1 + -0.01 + 0 + 0.2 + 1e+13 + 1 + + + + + + 1 + 1 + 1.9807 -1.95 0 0 -0 0 + + + 5352 597000000 + 1193 747345029 + 1672137622 292908372 + 591480 + + 3.26 0.388652 0 0 -0 1.5708 + 1 1 1 + + 3.26 0.388652 0 0 -0 1.5708 + 0 0 0 0 -0 0 + 0 0 0 0 -0 0 + 0 0 0 0 -0 0 + + + + 3.26 -0.811401 0 0 -0 1.5708 + 1 1 1 + + 3.26 -0.811401 0 0 -0 1.5708 + 0 0 0 0 -0 0 + 0 0 0 0 -0 0 + 0 0 0 0 -0 0 + + + + 3.26 -2 0 0 -0 1.5708 + 1 1 1 + + 3.26 -2 0 0 -0 1.5708 + 0 0 0 0 -0 0 + 0 0 0 0 -0 0 + 0 0 0 0 -0 0 + + + + -0.69 0.404037 0 0 0 -1.5708 + 1 1 1 + + -0.69 0.404037 0 0 0 -1.5708 + 0 0 0 0 -0 0 + 0 0 0 0 -0 0 + 0 0 0 0 -0 0 + + + + 2.6 0.95 0 0 -0 3.14159 + 1 1 1 + + 2.6 0.95 0 0 -0 3.14159 + 0 0 0 0 -0 0 + 0 0 0 0 -0 0 + 0 0 0 0 -0 0 + + + + 1.3 0.95 0 0 -0 3.14159 + 1 1 1 + + 1.3 0.95 0 0 -0 3.14159 + 0 0 0 0 -0 0 + 0 0 0 0 -0 0 + 0 0 0 0 -0 0 + + + + 0 0.947469 0 0 -0 3.14158 + 1 1 1 + + 0 0.947469 0 0 -0 3.14158 + 0 0 0 0 -0 0 + 0 0 0 0 -0 0 + 0 0 0 0 -0 0 + + + + 0 -2.54 0 0 -0 0 + 1 1 1 + + 0 -2.54 0 0 -0 0 + 0 0 0 0 -0 0 + 0 0 0 0 -0 0 + 0 0 0 0 -0 0 + + + + 1.3 -2.54 0 0 -0 0 + 1 1 1 + + 1.3 -2.54 0 0 -0 0 + 0 0 0 0 -0 0 + 0 0 0 0 -0 0 + 0 0 0 0 -0 0 + + + + 2.6 -2.54 0 0 -0 0 + 1 1 1 + + 2.6 -2.54 0 0 -0 0 + 0 0 0 0 -0 0 + 0 0 0 0 -0 0 + 0 0 0 0 -0 0 + + + + -0.69 -1.9807 0 0 0 -1.5708 + 1 1 1 + + -0.69 -1.9807 0 0 0 -1.5708 + 0 0 0 0 -0 0 + 0 0 0 0 -0 0 + 0 0 0 0 -0 0 + + + + 0 0 0 0 -0 0 + 1 1 1 + + 0 0 0 0 -0 0 + 0 0 0 0 -0 0 + 0 0 0 0 -0 0 + 0 0 0 0 -0 0 + + + + 1.935 -0.861944 0 0 -0 3.14159 + 1 1 1 + + 1.935 -0.861944 0 0 -0 3.14159 + 0 0 0 0 -0 0 + 0 0 0 0 -0 0 + 0 0 0 0 -0 0 + + + + 1.28 5e-06 -0 0 -0 1.5708 + 1 1 1 + + 1.28 5e-06 -0 0 -0 1.5708 + 0 0 0 0 -0 0 + 0 0 0 0 -0 0 + 0 0 0 0 -0 0 + + + + -1.1 0.742257 0 0 -0 3.14159 + 1 1 1 + + -1.1 0.742257 0 0 -0 3.14159 + 0 0 0 0 -0 0 + 0 0 0 0 -0 0 + 0 0 0 0 -0 0 + + + + -0.726743 -0.78522 0 0 0 -1.5708 + 1 1 1 + + -0.726743 -0.78522 0 0 0 -1.5708 + 0 0 0 0 -0 0 + 0 0 0 0 -0 0 + 0 0 0 0 -0 0 + + + + 0 0 10 0 -0 0 + + + + + 0.314835 2.08072 5.79785 0 1.1338 -1.52559 + orbit + perspective + + + + + + 1 + + 0.166667 + 0 + 0 + 0.166667 + 0 + 0.166667 + + 0 0 0 0 -0 0 + + 0 0 0 0 -0 0 + 1 + 0 + 0 + 0 + + 0 0 0 0 -0 0 + + + model://ifarlab_bus/model/ifarlab_bus.stl + 0.001 0.001 0.001 + + + + 1 + 1 0 0 1 + 1 0 0 1 + 0.1 0.1 0.1 1 + 0 0 0 0 + + 0 + 1 + + + 0 + 10 + 0 0 0 0 -0 0 + + + model://ifarlab_bus/model/ifarlab_bus.stl + 0.001 0.001 0.001 + + + + + + 1 + 1 + 0 0 0 + 0 + 0 + + + 1 + 0 + 0 + 1 + + 0 + + + + + 0 + 1e+06 + + + 0 + 1 + 1 + + 0 + 0.2 + 1e+13 + 1 + 0.01 + 0 + + + 1 + -0.01 + 0 + 0.2 + 1e+13 + 1 + + + + + + 1 + 1 + 5.2637 0.395216 0 0 -0 0 + + + diff --git a/mobile_manipulator/mobile_manipulator_description/meshes/ota/OTA-v0.7.zip b/mobile_manipulator/mobile_manipulator_description/meshes/ota/OTA-v0.7.zip new file mode 100644 index 0000000..13faf13 Binary files /dev/null and b/mobile_manipulator/mobile_manipulator_description/meshes/ota/OTA-v0.7.zip differ