├── .catkin_workspace ├── .gitignore ├── README.md ├── data ├── README.md ├── bag2csv.py ├── clean.sh ├── model │ ├── DatNet.py │ ├── DataSet.py │ ├── FLAGS.py │ ├── README.md │ ├── cnn.h5 │ ├── cnn.json │ ├── image_processor.py │ ├── model.py │ ├── pickle_generator.py │ └── train.py ├── train │ ├── DatNet.py │ ├── DataSet.py │ ├── DataSet.pyc │ ├── FLAGS.py │ ├── FLAGS.pyc │ ├── image_processor.py │ ├── pickle_generator.py │ └── train.py ├── transfer2host.sh └── transfer2host_pc.sh ├── docs ├── img │ ├── USB_ACM_SUPPORT.png │ ├── car.jpg │ ├── controller.jpg │ ├── custom-name.png │ └── jetson-car.jpg ├── research │ ├── DuckieTown_MIT │ │ └── duckietown_ros.pdf │ ├── architecture │ │ ├── computational_graph.png │ │ ├── hardware │ │ │ └── drawing_package.pdf │ │ ├── sensors_configuration.pdf │ │ └── system_architechture.png │ ├── obstacle_detection_using_stereo_vision.pdf │ ├── real_time_obs_avoidance.pdf │ └── utils │ │ ├── record_data.py │ │ └── test_motor.py ├── setup │ ├── README.md │ ├── drivers │ │ ├── razor_imu_m0_driver │ │ ├── rpm_monitor.ino │ │ └── teensy_driver.ino │ ├── ros_lib.zip │ ├── ros_lib │ │ ├── ArduinoHardware.h │ │ ├── actionlib │ │ │ ├── TestAction.h │ │ │ ├── TestActionFeedback.h │ │ │ ├── TestActionGoal.h │ │ │ ├── TestActionResult.h │ │ │ ├── TestFeedback.h │ │ │ ├── TestGoal.h │ │ │ ├── TestRequestAction.h │ │ │ ├── TestRequestActionFeedback.h │ │ │ ├── TestRequestActionGoal.h │ │ │ ├── TestRequestActionResult.h │ │ │ ├── TestRequestFeedback.h │ │ │ ├── TestRequestGoal.h │ │ │ ├── TestRequestResult.h │ │ │ ├── TestResult.h │ │ │ ├── TwoIntsAction.h │ │ │ ├── TwoIntsActionFeedback.h │ │ │ ├── TwoIntsActionGoal.h │ │ │ ├── TwoIntsActionResult.h │ │ │ ├── TwoIntsFeedback.h │ │ │ ├── TwoIntsGoal.h │ │ │ └── TwoIntsResult.h │ │ ├── actionlib_msgs │ │ │ ├── GoalID.h │ │ │ ├── GoalStatus.h │ │ │ └── GoalStatusArray.h │ │ ├── audio_common_msgs │ │ │ └── AudioData.h │ │ ├── bond │ │ │ ├── Constants.h │ │ │ └── Status.h │ │ ├── control_msgs │ │ │ ├── FollowJointTrajectoryAction.h │ │ │ ├── FollowJointTrajectoryActionFeedback.h │ │ │ ├── FollowJointTrajectoryActionGoal.h │ │ │ ├── FollowJointTrajectoryActionResult.h │ │ │ ├── FollowJointTrajectoryFeedback.h │ │ │ ├── FollowJointTrajectoryGoal.h │ │ │ ├── FollowJointTrajectoryResult.h │ │ │ ├── GripperCommand.h │ │ │ ├── GripperCommandAction.h │ │ │ ├── GripperCommandActionFeedback.h │ │ │ ├── GripperCommandActionGoal.h │ │ │ ├── GripperCommandActionResult.h │ │ │ ├── GripperCommandFeedback.h │ │ │ ├── GripperCommandGoal.h │ │ │ ├── GripperCommandResult.h │ │ │ ├── JointControllerState.h │ │ │ ├── JointTolerance.h │ │ │ ├── JointTrajectoryAction.h │ │ │ ├── JointTrajectoryActionFeedback.h │ │ │ ├── JointTrajectoryActionGoal.h │ │ │ ├── JointTrajectoryActionResult.h │ │ │ ├── JointTrajectoryControllerState.h │ │ │ ├── JointTrajectoryFeedback.h │ │ │ ├── JointTrajectoryGoal.h │ │ │ ├── JointTrajectoryResult.h │ │ │ ├── PidState.h │ │ │ ├── PointHeadAction.h │ │ │ ├── PointHeadActionFeedback.h │ │ │ ├── PointHeadActionGoal.h │ │ │ ├── PointHeadActionResult.h │ │ │ ├── PointHeadFeedback.h │ │ │ ├── PointHeadGoal.h │ │ │ ├── PointHeadResult.h │ │ │ ├── QueryCalibrationState.h │ │ │ ├── QueryTrajectoryState.h │ │ │ ├── SingleJointPositionAction.h │ │ │ ├── SingleJointPositionActionFeedback.h │ │ │ ├── SingleJointPositionActionGoal.h │ │ │ ├── SingleJointPositionActionResult.h │ │ │ ├── SingleJointPositionFeedback.h │ │ │ ├── SingleJointPositionGoal.h │ │ │ └── SingleJointPositionResult.h │ │ ├── controller_manager_msgs │ │ │ ├── ControllerState.h │ │ │ ├── ControllerStatistics.h │ │ │ ├── ControllersStatistics.h │ │ │ ├── HardwareInterfaceResources.h │ │ │ ├── ListControllerTypes.h │ │ │ ├── ListControllers.h │ │ │ ├── LoadController.h │ │ │ ├── ReloadControllerLibraries.h │ │ │ ├── SwitchController.h │ │ │ └── UnloadController.h │ │ ├── diagnostic_msgs │ │ │ ├── AddDiagnostics.h │ │ │ ├── DiagnosticArray.h │ │ │ ├── DiagnosticStatus.h │ │ │ ├── KeyValue.h │ │ │ └── SelfTest.h │ │ ├── duration.cpp │ │ ├── dynamic_reconfigure │ │ │ ├── BoolParameter.h │ │ │ ├── Config.h │ │ │ ├── ConfigDescription.h │ │ │ ├── DoubleParameter.h │ │ │ ├── Group.h │ │ │ ├── GroupState.h │ │ │ ├── IntParameter.h │ │ │ ├── ParamDescription.h │ │ │ ├── Reconfigure.h │ │ │ ├── SensorLevels.h │ │ │ └── StrParameter.h │ │ ├── dynamic_tf_publisher │ │ │ ├── AssocTF.h │ │ │ ├── DeleteTF.h │ │ │ ├── DissocTF.h │ │ │ └── SetDynamicTF.h │ │ ├── examples │ │ │ ├── ADC │ │ │ │ └── ADC.pde │ │ │ ├── Blink │ │ │ │ └── Blink.pde │ │ │ ├── BlinkM │ │ │ │ ├── BlinkM.pde │ │ │ │ └── BlinkM_funcs.h │ │ │ ├── Clapper │ │ │ │ └── Clapper.pde │ │ │ ├── HelloWorld │ │ │ │ └── HelloWorld.pde │ │ │ ├── IrRanger │ │ │ │ └── IrRanger.pde │ │ │ ├── Logging │ │ │ │ └── Logging.pde │ │ │ ├── Odom │ │ │ │ └── Odom.pde │ │ │ ├── ServiceClient │ │ │ │ ├── ServiceClient.pde │ │ │ │ └── client.py │ │ │ ├── ServiceServer │ │ │ │ └── ServiceServer.pde │ │ │ ├── ServoControl │ │ │ │ └── ServoControl.pde │ │ │ ├── Temperature │ │ │ │ └── Temperature.pde │ │ │ ├── TimeTF │ │ │ │ └── TimeTF.pde │ │ │ ├── Ultrasound │ │ │ │ └── Ultrasound.pde │ │ │ ├── button_example │ │ │ │ └── button_example.pde │ │ │ └── pubsub │ │ │ │ └── pubsub.pde │ │ ├── geometry_msgs │ │ │ ├── Accel.h │ │ │ ├── AccelStamped.h │ │ │ ├── AccelWithCovariance.h │ │ │ ├── AccelWithCovarianceStamped.h │ │ │ ├── Inertia.h │ │ │ ├── InertiaStamped.h │ │ │ ├── Point.h │ │ │ ├── Point32.h │ │ │ ├── PointStamped.h │ │ │ ├── Polygon.h │ │ │ ├── PolygonStamped.h │ │ │ ├── Pose.h │ │ │ ├── Pose2D.h │ │ │ ├── PoseArray.h │ │ │ ├── PoseStamped.h │ │ │ ├── PoseWithCovariance.h │ │ │ ├── PoseWithCovarianceStamped.h │ │ │ ├── Quaternion.h │ │ │ ├── QuaternionStamped.h │ │ │ ├── Transform.h │ │ │ ├── TransformStamped.h │ │ │ ├── Twist.h │ │ │ ├── TwistStamped.h │ │ │ ├── TwistWithCovariance.h │ │ │ ├── TwistWithCovarianceStamped.h │ │ │ ├── Vector3.h │ │ │ ├── Vector3Stamped.h │ │ │ ├── Wrench.h │ │ │ └── WrenchStamped.h │ │ ├── image_view2 │ │ │ ├── ChangeMode.h │ │ │ ├── ImageMarker2.h │ │ │ ├── MouseEvent.h │ │ │ └── PointArrayStamped.h │ │ ├── jsk_footstep_msgs │ │ │ ├── ExecFootstepsAction.h │ │ │ ├── ExecFootstepsActionFeedback.h │ │ │ ├── ExecFootstepsActionGoal.h │ │ │ ├── ExecFootstepsActionResult.h │ │ │ ├── ExecFootstepsFeedback.h │ │ │ ├── ExecFootstepsGoal.h │ │ │ ├── ExecFootstepsResult.h │ │ │ ├── Footstep.h │ │ │ ├── FootstepArray.h │ │ │ ├── PlanFootstepsAction.h │ │ │ ├── PlanFootstepsActionFeedback.h │ │ │ ├── PlanFootstepsActionGoal.h │ │ │ ├── PlanFootstepsActionResult.h │ │ │ ├── PlanFootstepsFeedback.h │ │ │ ├── PlanFootstepsGoal.h │ │ │ └── PlanFootstepsResult.h │ │ ├── jsk_recognition_msgs │ │ │ ├── Accuracy.h │ │ │ ├── BoolStamped.h │ │ │ ├── BoundingBox.h │ │ │ ├── BoundingBoxArray.h │ │ │ ├── BoundingBoxArrayWithCameraInfo.h │ │ │ ├── BoundingBoxMovement.h │ │ │ ├── CallPolygon.h │ │ │ ├── CallSnapIt.h │ │ │ ├── CheckCircle.h │ │ │ ├── CheckCollision.h │ │ │ ├── Circle2D.h │ │ │ ├── Circle2DArray.h │ │ │ ├── ClassificationResult.h │ │ │ ├── ClusterPointIndices.h │ │ │ ├── ColorHistogram.h │ │ │ ├── ColorHistogramArray.h │ │ │ ├── ContactSensor.h │ │ │ ├── ContactSensorArray.h │ │ │ ├── DepthCalibrationParameter.h │ │ │ ├── DepthErrorResult.h │ │ │ ├── EnvironmentLock.h │ │ │ ├── EuclideanSegment.h │ │ │ ├── HeightmapConfig.h │ │ │ ├── Histogram.h │ │ │ ├── HistogramWithRange.h │ │ │ ├── HistogramWithRangeArray.h │ │ │ ├── HistogramWithRangeBin.h │ │ │ ├── ICPAlign.h │ │ │ ├── ICPAlignWithBox.h │ │ │ ├── ICPResult.h │ │ │ ├── ImageDifferenceValue.h │ │ │ ├── Int32Stamped.h │ │ │ ├── Line.h │ │ │ ├── LineArray.h │ │ │ ├── ModelCoefficientsArray.h │ │ │ ├── NonMaximumSuppression.h │ │ │ ├── ParallelEdge.h │ │ │ ├── ParallelEdgeArray.h │ │ │ ├── PlotData.h │ │ │ ├── PlotDataArray.h │ │ │ ├── PointsArray.h │ │ │ ├── PolygonArray.h │ │ │ ├── PolygonOnEnvironment.h │ │ │ ├── PosedCameraInfo.h │ │ │ ├── Rect.h │ │ │ ├── RectArray.h │ │ │ ├── RobotPickupReleasePoint.h │ │ │ ├── RotatedRect.h │ │ │ ├── RotatedRectStamped.h │ │ │ ├── SetDepthCalibrationParameter.h │ │ │ ├── SetLabels.h │ │ │ ├── SetPointCloud2.h │ │ │ ├── SetTemplate.h │ │ │ ├── SimpleHandle.h │ │ │ ├── SimpleOccupancyGrid.h │ │ │ ├── SimpleOccupancyGridArray.h │ │ │ ├── SlicedPointCloud.h │ │ │ ├── SnapFootstep.h │ │ │ ├── SnapItRequest.h │ │ │ ├── SparseImage.h │ │ │ ├── SparseOccupancyGrid.h │ │ │ ├── SparseOccupancyGridArray.h │ │ │ ├── SparseOccupancyGridCell.h │ │ │ ├── SparseOccupancyGridColumn.h │ │ │ ├── SwitchTopic.h │ │ │ ├── TimeRange.h │ │ │ ├── Torus.h │ │ │ ├── TorusArray.h │ │ │ ├── TowerPickUp.h │ │ │ ├── TowerRobotMoveCommand.h │ │ │ ├── TrackerStatus.h │ │ │ ├── TransformScreenpoint.h │ │ │ ├── UpdateOffset.h │ │ │ ├── VectorArray.h │ │ │ ├── WeightedPoseArray.h │ │ │ ├── WhiteBalance.h │ │ │ └── WhiteBalancePoints.h │ │ ├── jsk_topic_tools │ │ │ ├── ChangeTopic.h │ │ │ ├── List.h │ │ │ ├── PassthroughDuration.h │ │ │ ├── TopicInfo.h │ │ │ └── Update.h │ │ ├── laser_assembler │ │ │ ├── AssembleScans.h │ │ │ └── AssembleScans2.h │ │ ├── map_msgs │ │ │ ├── GetMapROI.h │ │ │ ├── GetPointMap.h │ │ │ ├── GetPointMapROI.h │ │ │ ├── OccupancyGridUpdate.h │ │ │ ├── PointCloud2Update.h │ │ │ ├── ProjectedMap.h │ │ │ ├── ProjectedMapInfo.h │ │ │ ├── ProjectedMapsInfo.h │ │ │ ├── SaveMap.h │ │ │ └── SetMapProjections.h │ │ ├── moveit_msgs │ │ │ ├── AllowedCollisionEntry.h │ │ │ ├── AllowedCollisionMatrix.h │ │ │ ├── ApplyPlanningScene.h │ │ │ ├── AttachedCollisionObject.h │ │ │ ├── BoundingVolume.h │ │ │ ├── CheckIfRobotStateExistsInWarehouse.h │ │ │ ├── CollisionObject.h │ │ │ ├── ConstraintEvalResult.h │ │ │ ├── Constraints.h │ │ │ ├── ContactInformation.h │ │ │ ├── CostSource.h │ │ │ ├── DeleteRobotStateFromWarehouse.h │ │ │ ├── DisplayRobotState.h │ │ │ ├── DisplayTrajectory.h │ │ │ ├── ExecuteKnownTrajectory.h │ │ │ ├── ExecuteTrajectoryAction.h │ │ │ ├── ExecuteTrajectoryActionFeedback.h │ │ │ ├── ExecuteTrajectoryActionGoal.h │ │ │ ├── ExecuteTrajectoryActionResult.h │ │ │ ├── ExecuteTrajectoryFeedback.h │ │ │ ├── ExecuteTrajectoryGoal.h │ │ │ ├── ExecuteTrajectoryResult.h │ │ │ ├── GetCartesianPath.h │ │ │ ├── GetMotionPlan.h │ │ │ ├── GetPlannerParams.h │ │ │ ├── GetPlanningScene.h │ │ │ ├── GetPositionFK.h │ │ │ ├── GetPositionIK.h │ │ │ ├── GetRobotStateFromWarehouse.h │ │ │ ├── GetStateValidity.h │ │ │ ├── Grasp.h │ │ │ ├── GraspPlanning.h │ │ │ ├── GripperTranslation.h │ │ │ ├── JointConstraint.h │ │ │ ├── JointLimits.h │ │ │ ├── KinematicSolverInfo.h │ │ │ ├── LinkPadding.h │ │ │ ├── LinkScale.h │ │ │ ├── ListRobotStatesInWarehouse.h │ │ │ ├── LoadMap.h │ │ │ ├── MotionPlanDetailedResponse.h │ │ │ ├── MotionPlanRequest.h │ │ │ ├── MotionPlanResponse.h │ │ │ ├── MoveGroupAction.h │ │ │ ├── MoveGroupActionFeedback.h │ │ │ ├── MoveGroupActionGoal.h │ │ │ ├── MoveGroupActionResult.h │ │ │ ├── MoveGroupFeedback.h │ │ │ ├── MoveGroupGoal.h │ │ │ ├── MoveGroupResult.h │ │ │ ├── MoveItErrorCodes.h │ │ │ ├── ObjectColor.h │ │ │ ├── OrientationConstraint.h │ │ │ ├── OrientedBoundingBox.h │ │ │ ├── PickupAction.h │ │ │ ├── PickupActionFeedback.h │ │ │ ├── PickupActionGoal.h │ │ │ ├── PickupActionResult.h │ │ │ ├── PickupFeedback.h │ │ │ ├── PickupGoal.h │ │ │ ├── PickupResult.h │ │ │ ├── PlaceAction.h │ │ │ ├── PlaceActionFeedback.h │ │ │ ├── PlaceActionGoal.h │ │ │ ├── PlaceActionResult.h │ │ │ ├── PlaceFeedback.h │ │ │ ├── PlaceGoal.h │ │ │ ├── PlaceLocation.h │ │ │ ├── PlaceResult.h │ │ │ ├── PlannerInterfaceDescription.h │ │ │ ├── PlannerParams.h │ │ │ ├── PlanningOptions.h │ │ │ ├── PlanningScene.h │ │ │ ├── PlanningSceneComponents.h │ │ │ ├── PlanningSceneWorld.h │ │ │ ├── PositionConstraint.h │ │ │ ├── PositionIKRequest.h │ │ │ ├── QueryPlannerInterfaces.h │ │ │ ├── RenameRobotStateInWarehouse.h │ │ │ ├── RobotState.h │ │ │ ├── RobotTrajectory.h │ │ │ ├── SaveMap.h │ │ │ ├── SaveRobotStateToWarehouse.h │ │ │ ├── SetPlannerParams.h │ │ │ ├── TrajectoryConstraints.h │ │ │ ├── VisibilityConstraint.h │ │ │ └── WorkspaceParameters.h │ │ ├── nav_msgs │ │ │ ├── GetMap.h │ │ │ ├── GetMapAction.h │ │ │ ├── GetMapActionFeedback.h │ │ │ ├── GetMapActionGoal.h │ │ │ ├── GetMapActionResult.h │ │ │ ├── GetMapFeedback.h │ │ │ ├── GetMapGoal.h │ │ │ ├── GetMapResult.h │ │ │ ├── GetPlan.h │ │ │ ├── GridCells.h │ │ │ ├── MapMetaData.h │ │ │ ├── OccupancyGrid.h │ │ │ ├── Odometry.h │ │ │ ├── Path.h │ │ │ └── SetMap.h │ │ ├── nodelet │ │ │ ├── NodeletList.h │ │ │ ├── NodeletLoad.h │ │ │ └── NodeletUnload.h │ │ ├── object_recognition_msgs │ │ │ ├── GetObjectInformation.h │ │ │ ├── ObjectInformation.h │ │ │ ├── ObjectRecognitionAction.h │ │ │ ├── ObjectRecognitionActionFeedback.h │ │ │ ├── ObjectRecognitionActionGoal.h │ │ │ ├── ObjectRecognitionActionResult.h │ │ │ ├── ObjectRecognitionFeedback.h │ │ │ ├── ObjectRecognitionGoal.h │ │ │ ├── ObjectRecognitionResult.h │ │ │ ├── ObjectType.h │ │ │ ├── RecognizedObject.h │ │ │ ├── RecognizedObjectArray.h │ │ │ ├── Table.h │ │ │ └── TableArray.h │ │ ├── octomap_msgs │ │ │ ├── BoundingBoxQuery.h │ │ │ ├── GetOctomap.h │ │ │ ├── Octomap.h │ │ │ └── OctomapWithPose.h │ │ ├── openni2_camera │ │ │ └── GetSerial.h │ │ ├── pcl_msgs │ │ │ ├── ModelCoefficients.h │ │ │ ├── PointIndices.h │ │ │ ├── PolygonMesh.h │ │ │ └── Vertices.h │ │ ├── py_trees_msgs │ │ │ ├── Behaviour.h │ │ │ ├── BehaviourTree.h │ │ │ ├── CloseBlackboardWatcher.h │ │ │ ├── DockAction.h │ │ │ ├── DockActionFeedback.h │ │ │ ├── DockActionGoal.h │ │ │ ├── DockActionResult.h │ │ │ ├── DockFeedback.h │ │ │ ├── DockGoal.h │ │ │ ├── DockResult.h │ │ │ ├── GetBlackboardVariables.h │ │ │ ├── OpenBlackboardWatcher.h │ │ │ ├── RotateAction.h │ │ │ ├── RotateActionFeedback.h │ │ │ ├── RotateActionGoal.h │ │ │ ├── RotateActionResult.h │ │ │ ├── RotateFeedback.h │ │ │ ├── RotateGoal.h │ │ │ └── RotateResult.h │ │ ├── rc_car_msgs │ │ │ ├── CarController.h │ │ │ ├── CarInfo.h │ │ │ └── CarRecorder.h │ │ ├── realsense_camera │ │ │ ├── CameraConfiguration.h │ │ │ ├── ForcePower.h │ │ │ ├── GetIMUInfo.h │ │ │ ├── IMUInfo.h │ │ │ ├── IsPowered.h │ │ │ └── SetPower.h │ │ ├── rocon_service_pair_msgs │ │ │ ├── TestiesPair.h │ │ │ ├── TestiesPairRequest.h │ │ │ ├── TestiesPairResponse.h │ │ │ ├── TestiesRequest.h │ │ │ └── TestiesResponse.h │ │ ├── rocon_std_msgs │ │ │ ├── Connection.h │ │ │ ├── ConnectionCacheSpin.h │ │ │ ├── ConnectionsDiff.h │ │ │ ├── ConnectionsList.h │ │ │ ├── EmptyString.h │ │ │ ├── Float32Stamped.h │ │ │ ├── Icon.h │ │ │ ├── KeyValue.h │ │ │ ├── MasterInfo.h │ │ │ ├── Remapping.h │ │ │ ├── StringArray.h │ │ │ ├── Strings.h │ │ │ ├── StringsPair.h │ │ │ ├── StringsPairRequest.h │ │ │ ├── StringsPairResponse.h │ │ │ ├── StringsRequest.h │ │ │ └── StringsResponse.h │ │ ├── ros.h │ │ ├── ros │ │ │ ├── duration.h │ │ │ ├── msg.h │ │ │ ├── node_handle.h │ │ │ ├── publisher.h │ │ │ ├── service_client.h │ │ │ ├── service_server.h │ │ │ ├── subscriber.h │ │ │ └── time.h │ │ ├── roscpp │ │ │ ├── Empty.h │ │ │ ├── GetLoggers.h │ │ │ ├── Logger.h │ │ │ └── SetLoggerLevel.h │ │ ├── roscpp_tutorials │ │ │ └── TwoInts.h │ │ ├── rosgraph_msgs │ │ │ ├── Clock.h │ │ │ ├── Log.h │ │ │ └── TopicStatistics.h │ │ ├── rosserial_arduino │ │ │ ├── Adc.h │ │ │ └── Test.h │ │ ├── rosserial_msgs │ │ │ ├── Log.h │ │ │ ├── RequestMessageInfo.h │ │ │ ├── RequestParam.h │ │ │ ├── RequestServiceInfo.h │ │ │ └── TopicInfo.h │ │ ├── sensor_msgs │ │ │ ├── BatteryState.h │ │ │ ├── CameraInfo.h │ │ │ ├── ChannelFloat32.h │ │ │ ├── CompressedImage.h │ │ │ ├── FluidPressure.h │ │ │ ├── Illuminance.h │ │ │ ├── Image.h │ │ │ ├── Imu.h │ │ │ ├── JointState.h │ │ │ ├── Joy.h │ │ │ ├── JoyFeedback.h │ │ │ ├── JoyFeedbackArray.h │ │ │ ├── LaserEcho.h │ │ │ ├── LaserScan.h │ │ │ ├── MagneticField.h │ │ │ ├── MultiDOFJointState.h │ │ │ ├── MultiEchoLaserScan.h │ │ │ ├── NavSatFix.h │ │ │ ├── NavSatStatus.h │ │ │ ├── PointCloud.h │ │ │ ├── PointCloud2.h │ │ │ ├── PointField.h │ │ │ ├── Range.h │ │ │ ├── RegionOfInterest.h │ │ │ ├── RelativeHumidity.h │ │ │ ├── SetCameraInfo.h │ │ │ ├── Temperature.h │ │ │ └── TimeReference.h │ │ ├── shape_msgs │ │ │ ├── Mesh.h │ │ │ ├── MeshTriangle.h │ │ │ ├── Plane.h │ │ │ └── SolidPrimitive.h │ │ ├── sound_play │ │ │ ├── SoundRequest.h │ │ │ ├── SoundRequestAction.h │ │ │ ├── SoundRequestActionFeedback.h │ │ │ ├── SoundRequestActionGoal.h │ │ │ ├── SoundRequestActionResult.h │ │ │ ├── SoundRequestFeedback.h │ │ │ ├── SoundRequestGoal.h │ │ │ └── SoundRequestResult.h │ │ ├── std_msgs │ │ │ ├── Bool.h │ │ │ ├── Byte.h │ │ │ ├── ByteMultiArray.h │ │ │ ├── Char.h │ │ │ ├── ColorRGBA.h │ │ │ ├── Duration.h │ │ │ ├── Empty.h │ │ │ ├── Float32.h │ │ │ ├── Float32MultiArray.h │ │ │ ├── Float64.h │ │ │ ├── Float64MultiArray.h │ │ │ ├── Header.h │ │ │ ├── Int16.h │ │ │ ├── Int16MultiArray.h │ │ │ ├── Int32.h │ │ │ ├── Int32MultiArray.h │ │ │ ├── Int64.h │ │ │ ├── Int64MultiArray.h │ │ │ ├── Int8.h │ │ │ ├── Int8MultiArray.h │ │ │ ├── MultiArrayDimension.h │ │ │ ├── MultiArrayLayout.h │ │ │ ├── String.h │ │ │ ├── Time.h │ │ │ ├── UInt16.h │ │ │ ├── UInt16MultiArray.h │ │ │ ├── UInt32.h │ │ │ ├── UInt32MultiArray.h │ │ │ ├── UInt64.h │ │ │ ├── UInt64MultiArray.h │ │ │ ├── UInt8.h │ │ │ └── UInt8MultiArray.h │ │ ├── std_srvs │ │ │ ├── Empty.h │ │ │ ├── SetBool.h │ │ │ └── Trigger.h │ │ ├── stereo_msgs │ │ │ └── DisparityImage.h │ │ ├── tests │ │ │ ├── array_test │ │ │ │ └── array_test.pde │ │ │ ├── float64_test │ │ │ │ └── float64_test.pde │ │ │ └── time_test │ │ │ │ └── time_test.pde │ │ ├── tf │ │ │ ├── FrameGraph.h │ │ │ ├── tf.h │ │ │ ├── tfMessage.h │ │ │ └── transform_broadcaster.h │ │ ├── tf2_msgs │ │ │ ├── FrameGraph.h │ │ │ ├── LookupTransformAction.h │ │ │ ├── LookupTransformActionFeedback.h │ │ │ ├── LookupTransformActionGoal.h │ │ │ ├── LookupTransformActionResult.h │ │ │ ├── LookupTransformFeedback.h │ │ │ ├── LookupTransformGoal.h │ │ │ ├── LookupTransformResult.h │ │ │ ├── TF2Error.h │ │ │ └── TFMessage.h │ │ ├── time.cpp │ │ ├── topic_tools │ │ │ ├── DemuxAdd.h │ │ │ ├── DemuxDelete.h │ │ │ ├── DemuxList.h │ │ │ ├── DemuxSelect.h │ │ │ ├── MuxAdd.h │ │ │ ├── MuxDelete.h │ │ │ ├── MuxList.h │ │ │ └── MuxSelect.h │ │ ├── trajectory_msgs │ │ │ ├── JointTrajectory.h │ │ │ ├── JointTrajectoryPoint.h │ │ │ ├── MultiDOFJointTrajectory.h │ │ │ └── MultiDOFJointTrajectoryPoint.h │ │ ├── uuid_msgs │ │ │ └── UniqueID.h │ │ └── visualization_msgs │ │ │ ├── ImageMarker.h │ │ │ ├── InteractiveMarker.h │ │ │ ├── InteractiveMarkerControl.h │ │ │ ├── InteractiveMarkerFeedback.h │ │ │ ├── InteractiveMarkerInit.h │ │ │ ├── InteractiveMarkerPose.h │ │ │ ├── InteractiveMarkerUpdate.h │ │ │ ├── Marker.h │ │ │ ├── MarkerArray.h │ │ │ └── MenuEntry.h │ └── scripts │ │ ├── 1_installRos.sh │ │ └── 2_installDependencies.sh └── tiger_script │ ├── 0_run_all.sh │ ├── 1_make_custom_kernel.sh │ ├── 2_build_and_copy_kernel.sh │ ├── 3_install_ros.sh │ ├── 4_install_realsense.sh │ ├── 5_install_ros_realsense.sh │ ├── 6_setup_workspace.sh │ ├── README.md │ ├── enable_gpio_non_root │ ├── 99-com.rules │ ├── fix_udev_gpio.sh │ ├── gpio.sh │ └── setup_gpio.sh │ ├── mods │ ├── devfreq │ │ ├── Makefile │ │ └── Makefile (original) │ ├── nvadsp │ │ ├── Makefile (original).t18x │ │ └── Makefile.t18x │ ├── nvgpu │ │ ├── Makefile (original).nvgpu │ │ └── Makefile.nvgpu │ ├── rtcpu │ │ ├── Makefile (original).t18x │ │ └── Makefile.t18x │ └── sound │ │ ├── Makefile │ │ ├── Makefile (original) │ │ └── change.txt │ └── scripts │ ├── fixMakeFiles.sh │ └── realsense │ └── realsense-camera-formats.patch ├── model ├── basic_steering_model.h5 └── basic_steering_model.json └── src ├── CMakeLists.txt ├── controller ├── .activate.py.swp ├── CMakeLists.txt ├── FLAGS.py ├── Pilot.py ├── activate.py ├── cfg │ └── paths.yaml ├── include │ └── autopilot.h ├── launch │ ├── autopilot.launch │ ├── manual.launch │ └── manual.launch.old ├── package.xml └── src │ ├── DatNet.py │ ├── autopilot.cpp │ ├── controller.py │ └── joystick_node.cpp ├── navigation └── razor_imu_9dof │ ├── CMakeLists.txt │ ├── cfg │ └── imu.cfg │ ├── config │ ├── my_razor.yaml │ └── razor.yaml │ ├── launch │ ├── start.lauch │ └── start.launch │ ├── magnetometer_calibration │ ├── Matlab │ │ └── magnetometer_calibration │ │ │ ├── ellipsoid_fit.m │ │ │ ├── ellipsoid_fit_license.txt │ │ │ └── magnetometer_calibration.m │ └── Processing │ │ └── Magnetometer_calibration │ │ ├── Magnetometer_calibration.pde │ │ └── data │ │ └── Univers-66.vlw │ ├── nodes │ └── imu_node.py │ ├── package.xml │ ├── rviz │ └── imu_monitor.perspective │ └── src │ └── imu_driver │ ├── config.h │ └── imu_driver.ino ├── rc_car_msgs ├── CMakeLists.txt ├── msg │ ├── CarController.msg │ ├── CarInfo.msg │ └── CarRecorder.msg └── package.xml ├── record_data ├── CMakeLists.txt ├── launch │ ├── recorder.launch │ └── recorder.launch.old ├── package.xml ├── recorder.py └── src │ └── start.py └── vision ├── realsense_camera ├── CHANGELOG.rst ├── CMakeLists.txt ├── README.md ├── cfg │ ├── f200_params.cfg │ ├── r200_params.cfg │ ├── sr300_params.cfg │ └── zr300_params.cfg ├── include │ └── realsense_camera │ │ ├── base_nodelet.h │ │ ├── constants.h │ │ ├── f200_nodelet.h │ │ ├── r200_nodelet.h │ │ ├── sr300_nodelet.h │ │ ├── sync_nodelet.h │ │ └── zr300_nodelet.h ├── launch │ ├── f200_nodelet_default.launch │ ├── get_debug_info.launch │ ├── includes │ │ ├── nodelet.launch.xml │ │ └── nodelet_rgbd.launch.xml │ ├── r200_nodelet_default.launch │ ├── r200_nodelet_modify_params.launch │ ├── r200_nodelet_multiple_cameras.launch │ ├── r200_nodelet_rgbd.launch │ ├── sr300_nodelet_default.launch │ ├── sr300_nodelet_rgbd.launch │ ├── start.launch │ ├── zr300_nodelet_default.launch │ └── zr300_nodelet_rgdb.launch ├── librealsense ├── licenses │ └── License.txt ├── msg │ └── IMUInfo.msg ├── nodelet_plugins.xml ├── package.xml ├── rviz │ ├── realsenseRvizConfiguration1.rviz │ ├── realsenseRvizConfiguration2.rviz │ ├── realsenseRvizConfiguration3.rviz │ ├── realsense_default.rviz │ └── realsense_rgbd_pointcloud.rviz ├── src │ ├── base_nodelet.cpp │ ├── f200_nodelet.cpp │ ├── get_debug_info.cpp │ ├── r200_nodelet.cpp │ ├── sr300_nodelet.cpp │ ├── sync_nodelet.cpp │ └── zr300_nodelet.cpp ├── srv │ ├── CameraConfiguration.srv │ ├── ForcePower.srv │ ├── GetIMUInfo.srv │ ├── IsPowered.srv │ └── SetPower.srv └── test │ ├── camera_core.cpp │ ├── camera_core.h │ ├── f200_nodelet_camera_options.test │ ├── f200_nodelet_disable_color.test │ ├── f200_nodelet_disable_depth.test │ ├── f200_nodelet_enable_ir.test │ ├── f200_nodelet_modify_params.test │ ├── f200_nodelet_resolution.test │ ├── f200_nodelet_rgbd.test │ ├── files │ ├── bat-tests │ │ ├── check_librealsense_installed.test │ │ ├── check_realsense_camera_nodelet_built.test │ │ ├── f200_camera_info_matrix_check.test │ │ ├── f200_nodelet_camera_service_power_force_off_and_on_with_subscriber.test │ │ ├── f200_nodelet_camera_service_power_set_off_and_on_with_no_subscriber.test │ │ ├── f200_nodelet_transforms_enable_publish_tf.test │ │ ├── r200_camera_info_matrix_check.test │ │ ├── r200_nodelet_camera_service_power_force_off_and_on_with_subscriber.test │ │ ├── r200_nodelet_camera_service_power_set_off_and_on_with_no_subscriber.test │ │ ├── r200_nodelet_transforms_enable_publish_tf.test │ │ ├── sr300_camera_info_matrix_check.test │ │ ├── sr300_nodelet_camera_service_power_force_off_and_on_with_subscriber.test │ │ ├── sr300_nodelet_camera_service_power_set_off_and_on_with_no_subscriber.test │ │ ├── sr300_nodelet_transforms_enable_publish_tf.test │ │ ├── zr300_camera_info_matrix_check.test │ │ ├── zr300_nodelet_camera_service_power_force_off_and_on_with_subscriber.test │ │ ├── zr300_nodelet_camera_service_power_set_off_and_on_with_no_subscriber.test │ │ └── zr300_nodelet_transforms_enable_publish_tf.test │ └── scripts │ │ ├── check_camera_info_matrix.py │ │ ├── check_camera_service_power_force_off_and_on_with_subscriber.py │ │ ├── check_camera_service_power_set_off_and_on_with_no_subscriber.py │ │ ├── check_camera_transforms_publish_tf.py │ │ ├── check_librealsense_installed.py │ │ ├── check_realsense_camera_nodelet_built.py │ │ ├── libs │ │ ├── roscd.bash │ │ ├── roscd_path.bash │ │ └── roscp.bash │ │ └── rs_general │ │ ├── __init__.py │ │ └── rs_general.py │ ├── r200_nodelet_camera_options.test │ ├── r200_nodelet_disable_color.test │ ├── r200_nodelet_disable_depth.test │ ├── r200_nodelet_enable_ir.test │ ├── r200_nodelet_modify_params.test │ ├── r200_nodelet_resolution.test │ ├── r200_nodelet_rgbd.test │ ├── rgbd_topics.cpp │ ├── rgbd_topics.h │ ├── sr300_nodelet_camera_options.test │ ├── sr300_nodelet_disable_color.test │ ├── sr300_nodelet_disable_depth.test │ ├── sr300_nodelet_enable_ir.test │ ├── sr300_nodelet_modify_params.test │ ├── sr300_nodelet_resolution.test │ ├── sr300_nodelet_rgbd.test │ └── zr300_nodelet_default.test ├── start.launch └── usb_cam ├── AUTHORS.md ├── CHANGELOG.rst ├── CMakeLists.txt ├── include └── usb_cam │ └── usb_cam.h ├── launch ├── start.launch └── usb_cam.launch ├── nodes └── usb_cam_node.cpp ├── package.xml └── src ├── LICENSE └── usb_cam.cpp /.catkin_workspace: -------------------------------------------------------------------------------- 1 | # This file currently only serves to mark the location of a catkin workspace for tool integration 2 | -------------------------------------------------------------------------------- /.gitignore: -------------------------------------------------------------------------------- 1 | .idea/ 2 | devel/ 3 | build/ 4 | .src/cmake-build-debug/ 5 | src/cmake-build-debug/ 6 | -------------------------------------------------------------------------------- /data/README.md: -------------------------------------------------------------------------------- 1 | This directory store collected data from jetson car and some utilities to extract data for training the Driving Model. 2 | -------------------------------------------------------------------------------- /data/clean.sh: -------------------------------------------------------------------------------- 1 | #!/bin/bash 2 | # Remove driving log record for new dataset 3 | rm -rf ./imgs/* ./depth_imgs/* driving_log.csv 4 | -------------------------------------------------------------------------------- /data/model/FLAGS.py: -------------------------------------------------------------------------------- 1 | # Image Size 2 | HEIGHT = 46 # sky is removed .. in train.py 3 | WIDTH = 160 4 | CHANNELS = 3 5 | # Cropping factor 6 | CROP_TOP = 30 7 | CROP_BOTTOM = 5 8 | # output dimension from RNN 9 | OUTPUT_DIM = 3 # Steer, throttle, velocity 10 | # RNN SIZE 11 | HIDDEN_UNITS = 64 12 | STEER_CORRECTION = 0.2 13 | # HYPER-PARAMETER 14 | LOAD_WEIGHT = True 15 | LEARN_RATE = 0.001 16 | KEEP_PROP = 0.4 17 | EPOCHS = 1 18 | BATCH_SIZE = 4 # Be careful, stateful RNN requires to state batch size ahead 19 | TIME_STEPS = 10 # For RNN 20 | INIT = 'he_uniform' 21 | 22 | 23 | 24 | -------------------------------------------------------------------------------- /data/model/README.md: -------------------------------------------------------------------------------- 1 | This directory stores pre-trained Network for the driving model. 2 | 3 | ### `model.py` 4 | --------------- 5 | Desribe the network architecture 6 | 7 | ## How to train a new model 8 | 1. Create pickle file 9 | ``` 10 | python pickle_generator.py 11 | ``` 12 | 2. Train fine-tuned model 13 | ``` 14 | python train.py 15 | ``` 16 | 17 | -------------------------------------------------------------------------------- /data/model/cnn.h5: -------------------------------------------------------------------------------- https://raw.githubusercontent.com/datlife/jetson-car/a1bae7b8ad2af8ef9fd33cdd76421ebe3ff5ca7f/data/model/cnn.h5 -------------------------------------------------------------------------------- /data/model/image_processor.py: -------------------------------------------------------------------------------- 1 | import cv2 2 | import numpy as np 3 | 4 | 5 | def random_transform(img): 6 | # There are total of 6 transformation 7 | # I will create an boolean array of 6 elements [ 0 or 1] 8 | a = np.random.randint(0, 2, [1, 5]).astype('bool')[0] 9 | flip_angle = 1 10 | if a[1] == 1: 11 | img = rotate(img) 12 | # if a[2] == 1: 13 | # img = flip(img) 14 | # flip_angle = -1 # to swap the steering angle 15 | if a[3] == 1: 16 | img = blur(img) 17 | if a[4] == 1: 18 | img = gamma(img) 19 | return img, flip_angle 20 | 21 | 22 | def rotate(img): 23 | row, col, channel = img.shape 24 | angle = np.random.uniform(-15, 15) 25 | rotation_point = (row / 2, col / 2) 26 | rotation_matrix = cv2.getRotationMatrix2D(rotation_point, angle, 1) 27 | rotated_img = cv2.warpAffine(img, rotation_matrix, (col, row)) 28 | return rotated_img 29 | 30 | 31 | def gamma(img): 32 | gamma = np.random.uniform(0.5, 1.2) 33 | invGamma = 1.0 / gamma 34 | table = np.array([((i / 255.0) ** invGamma) * 255 for i in np.arange(0, 256)]).astype("uint8") 35 | new_img = cv2.LUT(img, table) 36 | return new_img 37 | 38 | 39 | def blur(img): 40 | r_int = np.random.randint(0, 2) 41 | odd_size = 2 * r_int + 1 42 | return cv2.GaussianBlur(img, (odd_size, odd_size), 0) 43 | 44 | 45 | def flip(img): 46 | return cv2.flip(img, 1) 47 | 48 | 49 | 50 | -------------------------------------------------------------------------------- /data/model/pickle_generator.py: -------------------------------------------------------------------------------- 1 | # This script is used to generate pickle file from Udacity car simulator. 2 | # It will allow me to reuse dataset easier. 3 | 4 | # Change LOG_PATH and IMG_PATH to generate new file 5 | import pickle 6 | from FLAGS import * 7 | from DataSet import DataSet 8 | import matplotlib.pyplot as plt 9 | import numpy as np 10 | import matplotlib.pyplot as plt 11 | import numpy as np 12 | import matplotlib.gridspec as grid 13 | plt.interactive(False) 14 | 15 | LOG_PATH = '../straight/driving_log.csv' 16 | IMG_PATH = '../straight/imgs/' 17 | FILE_NAME = '../straight.p' 18 | 19 | data = DataSet(LOG_PATH, IMG_PATH, sequence=TIME_STEPS) 20 | 21 | features, labels = data.build_train_data() 22 | pickle.dump({'features': features, 'labels': labels}, open(FILE_NAME, 'wb')) 23 | 24 | 25 | fig = plt.figure(figsize=(40, 40)) 26 | idx = 6 27 | gs = grid.GridSpec(idx, idx) 28 | 29 | # VISUALIZE FRAME + STEER VALUES for i in range(): 30 | for i in range(idx): 31 | for j in range(idx): 32 | r = np.random.choice(len(features)) 33 | img = features[r] 34 | ax = fig.add_subplot(gs[i*idx + j]) 35 | title = "ID: {} Steer {:5.3f} Speed {:5.3f} ".format(r, labels[r][0], labels[r][1]) 36 | ax.set_title(title) 37 | ax.axis('off') 38 | ax.imshow(img) 39 | gs.tight_layout(fig) 40 | plt.show() 41 | -------------------------------------------------------------------------------- /data/train/DataSet.pyc: -------------------------------------------------------------------------------- https://raw.githubusercontent.com/datlife/jetson-car/a1bae7b8ad2af8ef9fd33cdd76421ebe3ff5ca7f/data/train/DataSet.pyc -------------------------------------------------------------------------------- /data/train/FLAGS.py: -------------------------------------------------------------------------------- 1 | # Image Size 2 | HEIGHT = 46 # sky is removed .. in train.py 3 | WIDTH = 160 4 | CHANNELS = 3 5 | # Cropping factor 6 | CROP_TOP = 30 7 | CROP_BOTTOM = 5 8 | # output dimension from RNN 9 | OUTPUT_DIM = 2 # Steer, throttle, brake 10 | # RNN SIZE 11 | HIDDEN_UNITS = 64 12 | STEER_CORRECTION = 0.2 13 | # HYPER-PARAMETER 14 | LOAD_WEIGHT = True 15 | LEARN_RATE = 0.001 16 | KEEP_PROP = 0.4 17 | EPOCHS = 1 18 | BATCH_SIZE = 4 # Be careful, stateful RNN requires to state batch size ahead 19 | TIME_STEPS = 10 # For RNN 20 | INIT = 'he_uniform' 21 | 22 | 23 | 24 | -------------------------------------------------------------------------------- /data/train/FLAGS.pyc: -------------------------------------------------------------------------------- https://raw.githubusercontent.com/datlife/jetson-car/a1bae7b8ad2af8ef9fd33cdd76421ebe3ff5ca7f/data/train/FLAGS.pyc -------------------------------------------------------------------------------- /data/train/image_processor.py: -------------------------------------------------------------------------------- 1 | import cv2 2 | import numpy as np 3 | 4 | 5 | def random_transform(img): 6 | # There are total of 6 transformation 7 | # I will create an boolean array of 6 elements [ 0 or 1] 8 | a = np.random.randint(0, 2, [1, 5]).astype('bool')[0] 9 | flip_angle = 1 10 | if a[1] == 1: 11 | img = rotate(img) 12 | # if a[2] == 1: 13 | # img = flip(img) 14 | # flip_angle = -1 # to swap the steering angle 15 | if a[3] == 1: 16 | img = blur(img) 17 | if a[4] == 1: 18 | img = gamma(img) 19 | return img, flip_angle 20 | 21 | 22 | def rotate(img): 23 | row, col, channel = img.shape 24 | angle = np.random.uniform(-15, 15) 25 | rotation_point = (row / 2, col / 2) 26 | rotation_matrix = cv2.getRotationMatrix2D(rotation_point, angle, 1) 27 | rotated_img = cv2.warpAffine(img, rotation_matrix, (col, row)) 28 | return rotated_img 29 | 30 | 31 | def gamma(img): 32 | gamma = np.random.uniform(0.5, 1.2) 33 | invGamma = 1.0 / gamma 34 | table = np.array([((i / 255.0) ** invGamma) * 255 for i in np.arange(0, 256)]).astype("uint8") 35 | new_img = cv2.LUT(img, table) 36 | return new_img 37 | 38 | 39 | def blur(img): 40 | r_int = np.random.randint(0, 2) 41 | odd_size = 2 * r_int + 1 42 | return cv2.GaussianBlur(img, (odd_size, odd_size), 0) 43 | 44 | 45 | def flip(img): 46 | return cv2.flip(img, 1) 47 | 48 | 49 | 50 | -------------------------------------------------------------------------------- /data/train/pickle_generator.py: -------------------------------------------------------------------------------- 1 | # This script is used to generate pickle file from Udacity car simulator. 2 | # It will allow me to reuse dataset easier. 3 | 4 | # Change LOG_PATH and IMG_PATH to generate new file 5 | import pickle 6 | from FLAGS import * 7 | from DataSet import DataSet 8 | import matplotlib.pyplot as plt 9 | import numpy as np 10 | 11 | LOG_PATH = './driving_log.csv' 12 | IMG_PATH = '/home/nvidia/bag/imgs/' 13 | FILE_NAME = '/home/nvidia/bag/test_pickle.p' 14 | 15 | data = DataSet(LOG_PATH, IMG_PATH, sequence=TIME_STEPS) 16 | 17 | features, labels = data.build_train_data() 18 | pickle.dump({'features': features, 'labels': labels}, open(FILE_NAME, 'wb')) 19 | 20 | -------------------------------------------------------------------------------- /data/transfer2host.sh: -------------------------------------------------------------------------------- 1 | #!/bin/bash 2 | # Copy Driving Log to host computer for computing 3 | scp -r driving_log.csv imgs depth_imgs datinfo@10.42.0.164:/home/datinfo/bag 4 | -------------------------------------------------------------------------------- /data/transfer2host_pc.sh: -------------------------------------------------------------------------------- 1 | #!/bin/bash 2 | # Copy Driving Log to host computer for computing 3 | scp -r driving_log.csv imgs depth_imgs datinfo@10.42.0.164:/home/datinfo/bag 4 | -------------------------------------------------------------------------------- /docs/img/USB_ACM_SUPPORT.png: -------------------------------------------------------------------------------- https://raw.githubusercontent.com/datlife/jetson-car/a1bae7b8ad2af8ef9fd33cdd76421ebe3ff5ca7f/docs/img/USB_ACM_SUPPORT.png -------------------------------------------------------------------------------- /docs/img/car.jpg: -------------------------------------------------------------------------------- https://raw.githubusercontent.com/datlife/jetson-car/a1bae7b8ad2af8ef9fd33cdd76421ebe3ff5ca7f/docs/img/car.jpg -------------------------------------------------------------------------------- /docs/img/controller.jpg: -------------------------------------------------------------------------------- https://raw.githubusercontent.com/datlife/jetson-car/a1bae7b8ad2af8ef9fd33cdd76421ebe3ff5ca7f/docs/img/controller.jpg -------------------------------------------------------------------------------- /docs/img/custom-name.png: -------------------------------------------------------------------------------- https://raw.githubusercontent.com/datlife/jetson-car/a1bae7b8ad2af8ef9fd33cdd76421ebe3ff5ca7f/docs/img/custom-name.png -------------------------------------------------------------------------------- /docs/img/jetson-car.jpg: -------------------------------------------------------------------------------- https://raw.githubusercontent.com/datlife/jetson-car/a1bae7b8ad2af8ef9fd33cdd76421ebe3ff5ca7f/docs/img/jetson-car.jpg -------------------------------------------------------------------------------- /docs/research/DuckieTown_MIT/duckietown_ros.pdf: -------------------------------------------------------------------------------- https://raw.githubusercontent.com/datlife/jetson-car/a1bae7b8ad2af8ef9fd33cdd76421ebe3ff5ca7f/docs/research/DuckieTown_MIT/duckietown_ros.pdf -------------------------------------------------------------------------------- /docs/research/architecture/computational_graph.png: -------------------------------------------------------------------------------- https://raw.githubusercontent.com/datlife/jetson-car/a1bae7b8ad2af8ef9fd33cdd76421ebe3ff5ca7f/docs/research/architecture/computational_graph.png -------------------------------------------------------------------------------- /docs/research/architecture/hardware/drawing_package.pdf: -------------------------------------------------------------------------------- https://raw.githubusercontent.com/datlife/jetson-car/a1bae7b8ad2af8ef9fd33cdd76421ebe3ff5ca7f/docs/research/architecture/hardware/drawing_package.pdf -------------------------------------------------------------------------------- /docs/research/architecture/sensors_configuration.pdf: -------------------------------------------------------------------------------- https://raw.githubusercontent.com/datlife/jetson-car/a1bae7b8ad2af8ef9fd33cdd76421ebe3ff5ca7f/docs/research/architecture/sensors_configuration.pdf -------------------------------------------------------------------------------- /docs/research/architecture/system_architechture.png: -------------------------------------------------------------------------------- https://raw.githubusercontent.com/datlife/jetson-car/a1bae7b8ad2af8ef9fd33cdd76421ebe3ff5ca7f/docs/research/architecture/system_architechture.png -------------------------------------------------------------------------------- /docs/research/obstacle_detection_using_stereo_vision.pdf: -------------------------------------------------------------------------------- https://raw.githubusercontent.com/datlife/jetson-car/a1bae7b8ad2af8ef9fd33cdd76421ebe3ff5ca7f/docs/research/obstacle_detection_using_stereo_vision.pdf -------------------------------------------------------------------------------- /docs/research/real_time_obs_avoidance.pdf: -------------------------------------------------------------------------------- https://raw.githubusercontent.com/datlife/jetson-car/a1bae7b8ad2af8ef9fd33cdd76421ebe3ff5ca7f/docs/research/real_time_obs_avoidance.pdf -------------------------------------------------------------------------------- /docs/research/utils/record_data.py: -------------------------------------------------------------------------------- 1 | PATH = './trainig_data/' 2 | -------------------------------------------------------------------------------- /docs/setup/drivers/razor_imu_m0_driver: -------------------------------------------------------------------------------- 1 | ../../src/navigation/razor_imu_m0/src/imu_driver/ -------------------------------------------------------------------------------- /docs/setup/ros_lib.zip: -------------------------------------------------------------------------------- https://raw.githubusercontent.com/datlife/jetson-car/a1bae7b8ad2af8ef9fd33cdd76421ebe3ff5ca7f/docs/setup/ros_lib.zip -------------------------------------------------------------------------------- /docs/setup/ros_lib/actionlib/TestRequestFeedback.h: -------------------------------------------------------------------------------- 1 | #ifndef _ROS_actionlib_TestRequestFeedback_h 2 | #define _ROS_actionlib_TestRequestFeedback_h 3 | 4 | #include 5 | #include 6 | #include 7 | #include "ros/msg.h" 8 | 9 | namespace actionlib 10 | { 11 | 12 | class TestRequestFeedback : public ros::Msg 13 | { 14 | public: 15 | 16 | TestRequestFeedback() 17 | { 18 | } 19 | 20 | virtual int serialize(unsigned char *outbuffer) const 21 | { 22 | int offset = 0; 23 | return offset; 24 | } 25 | 26 | virtual int deserialize(unsigned char *inbuffer) 27 | { 28 | int offset = 0; 29 | return offset; 30 | } 31 | 32 | const char * getType(){ return "actionlib/TestRequestFeedback"; }; 33 | const char * getMD5(){ return "d41d8cd98f00b204e9800998ecf8427e"; }; 34 | 35 | }; 36 | 37 | } 38 | #endif -------------------------------------------------------------------------------- /docs/setup/ros_lib/actionlib/TwoIntsFeedback.h: -------------------------------------------------------------------------------- 1 | #ifndef _ROS_actionlib_TwoIntsFeedback_h 2 | #define _ROS_actionlib_TwoIntsFeedback_h 3 | 4 | #include 5 | #include 6 | #include 7 | #include "ros/msg.h" 8 | 9 | namespace actionlib 10 | { 11 | 12 | class TwoIntsFeedback : public ros::Msg 13 | { 14 | public: 15 | 16 | TwoIntsFeedback() 17 | { 18 | } 19 | 20 | virtual int serialize(unsigned char *outbuffer) const 21 | { 22 | int offset = 0; 23 | return offset; 24 | } 25 | 26 | virtual int deserialize(unsigned char *inbuffer) 27 | { 28 | int offset = 0; 29 | return offset; 30 | } 31 | 32 | const char * getType(){ return "actionlib/TwoIntsFeedback"; }; 33 | const char * getMD5(){ return "d41d8cd98f00b204e9800998ecf8427e"; }; 34 | 35 | }; 36 | 37 | } 38 | #endif -------------------------------------------------------------------------------- /docs/setup/ros_lib/bond/Constants.h: -------------------------------------------------------------------------------- 1 | #ifndef _ROS_bond_Constants_h 2 | #define _ROS_bond_Constants_h 3 | 4 | #include 5 | #include 6 | #include 7 | #include "ros/msg.h" 8 | 9 | namespace bond 10 | { 11 | 12 | class Constants : public ros::Msg 13 | { 14 | public: 15 | enum { DEAD_PUBLISH_PERIOD = 0.05 }; 16 | enum { DEFAULT_CONNECT_TIMEOUT = 10.0 }; 17 | enum { DEFAULT_HEARTBEAT_TIMEOUT = 4.0 }; 18 | enum { DEFAULT_DISCONNECT_TIMEOUT = 2.0 }; 19 | enum { DEFAULT_HEARTBEAT_PERIOD = 1.0 }; 20 | enum { DISABLE_HEARTBEAT_TIMEOUT_PARAM = /bond_disable_heartbeat_timeout }; 21 | 22 | Constants() 23 | { 24 | } 25 | 26 | virtual int serialize(unsigned char *outbuffer) const 27 | { 28 | int offset = 0; 29 | return offset; 30 | } 31 | 32 | virtual int deserialize(unsigned char *inbuffer) 33 | { 34 | int offset = 0; 35 | return offset; 36 | } 37 | 38 | const char * getType(){ return "bond/Constants"; }; 39 | const char * getMD5(){ return "6fc594dc1d7bd7919077042712f8c8b0"; }; 40 | 41 | }; 42 | 43 | } 44 | #endif -------------------------------------------------------------------------------- /docs/setup/ros_lib/control_msgs/GripperCommand.h: -------------------------------------------------------------------------------- 1 | #ifndef _ROS_control_msgs_GripperCommand_h 2 | #define _ROS_control_msgs_GripperCommand_h 3 | 4 | #include 5 | #include 6 | #include 7 | #include "ros/msg.h" 8 | 9 | namespace control_msgs 10 | { 11 | 12 | class GripperCommand : public ros::Msg 13 | { 14 | public: 15 | typedef float _position_type; 16 | _position_type position; 17 | typedef float _max_effort_type; 18 | _max_effort_type max_effort; 19 | 20 | GripperCommand(): 21 | position(0), 22 | max_effort(0) 23 | { 24 | } 25 | 26 | virtual int serialize(unsigned char *outbuffer) const 27 | { 28 | int offset = 0; 29 | offset += serializeAvrFloat64(outbuffer + offset, this->position); 30 | offset += serializeAvrFloat64(outbuffer + offset, this->max_effort); 31 | return offset; 32 | } 33 | 34 | virtual int deserialize(unsigned char *inbuffer) 35 | { 36 | int offset = 0; 37 | offset += deserializeAvrFloat64(inbuffer + offset, &(this->position)); 38 | offset += deserializeAvrFloat64(inbuffer + offset, &(this->max_effort)); 39 | return offset; 40 | } 41 | 42 | const char * getType(){ return "control_msgs/GripperCommand"; }; 43 | const char * getMD5(){ return "680acaff79486f017132a7f198d40f08"; }; 44 | 45 | }; 46 | 47 | } 48 | #endif -------------------------------------------------------------------------------- /docs/setup/ros_lib/control_msgs/GripperCommandGoal.h: -------------------------------------------------------------------------------- 1 | #ifndef _ROS_control_msgs_GripperCommandGoal_h 2 | #define _ROS_control_msgs_GripperCommandGoal_h 3 | 4 | #include 5 | #include 6 | #include 7 | #include "ros/msg.h" 8 | #include "control_msgs/GripperCommand.h" 9 | 10 | namespace control_msgs 11 | { 12 | 13 | class GripperCommandGoal : public ros::Msg 14 | { 15 | public: 16 | typedef control_msgs::GripperCommand _command_type; 17 | _command_type command; 18 | 19 | GripperCommandGoal(): 20 | command() 21 | { 22 | } 23 | 24 | virtual int serialize(unsigned char *outbuffer) const 25 | { 26 | int offset = 0; 27 | offset += this->command.serialize(outbuffer + offset); 28 | return offset; 29 | } 30 | 31 | virtual int deserialize(unsigned char *inbuffer) 32 | { 33 | int offset = 0; 34 | offset += this->command.deserialize(inbuffer + offset); 35 | return offset; 36 | } 37 | 38 | const char * getType(){ return "control_msgs/GripperCommandGoal"; }; 39 | const char * getMD5(){ return "86fd82f4ddc48a4cb6856cfa69217e43"; }; 40 | 41 | }; 42 | 43 | } 44 | #endif -------------------------------------------------------------------------------- /docs/setup/ros_lib/control_msgs/JointTrajectoryFeedback.h: -------------------------------------------------------------------------------- 1 | #ifndef _ROS_control_msgs_JointTrajectoryFeedback_h 2 | #define _ROS_control_msgs_JointTrajectoryFeedback_h 3 | 4 | #include 5 | #include 6 | #include 7 | #include "ros/msg.h" 8 | 9 | namespace control_msgs 10 | { 11 | 12 | class JointTrajectoryFeedback : public ros::Msg 13 | { 14 | public: 15 | 16 | JointTrajectoryFeedback() 17 | { 18 | } 19 | 20 | virtual int serialize(unsigned char *outbuffer) const 21 | { 22 | int offset = 0; 23 | return offset; 24 | } 25 | 26 | virtual int deserialize(unsigned char *inbuffer) 27 | { 28 | int offset = 0; 29 | return offset; 30 | } 31 | 32 | const char * getType(){ return "control_msgs/JointTrajectoryFeedback"; }; 33 | const char * getMD5(){ return "d41d8cd98f00b204e9800998ecf8427e"; }; 34 | 35 | }; 36 | 37 | } 38 | #endif -------------------------------------------------------------------------------- /docs/setup/ros_lib/control_msgs/JointTrajectoryGoal.h: -------------------------------------------------------------------------------- 1 | #ifndef _ROS_control_msgs_JointTrajectoryGoal_h 2 | #define _ROS_control_msgs_JointTrajectoryGoal_h 3 | 4 | #include 5 | #include 6 | #include 7 | #include "ros/msg.h" 8 | #include "trajectory_msgs/JointTrajectory.h" 9 | 10 | namespace control_msgs 11 | { 12 | 13 | class JointTrajectoryGoal : public ros::Msg 14 | { 15 | public: 16 | typedef trajectory_msgs::JointTrajectory _trajectory_type; 17 | _trajectory_type trajectory; 18 | 19 | JointTrajectoryGoal(): 20 | trajectory() 21 | { 22 | } 23 | 24 | virtual int serialize(unsigned char *outbuffer) const 25 | { 26 | int offset = 0; 27 | offset += this->trajectory.serialize(outbuffer + offset); 28 | return offset; 29 | } 30 | 31 | virtual int deserialize(unsigned char *inbuffer) 32 | { 33 | int offset = 0; 34 | offset += this->trajectory.deserialize(inbuffer + offset); 35 | return offset; 36 | } 37 | 38 | const char * getType(){ return "control_msgs/JointTrajectoryGoal"; }; 39 | const char * getMD5(){ return "2a0eff76c870e8595636c2a562ca298e"; }; 40 | 41 | }; 42 | 43 | } 44 | #endif -------------------------------------------------------------------------------- /docs/setup/ros_lib/control_msgs/JointTrajectoryResult.h: -------------------------------------------------------------------------------- 1 | #ifndef _ROS_control_msgs_JointTrajectoryResult_h 2 | #define _ROS_control_msgs_JointTrajectoryResult_h 3 | 4 | #include 5 | #include 6 | #include 7 | #include "ros/msg.h" 8 | 9 | namespace control_msgs 10 | { 11 | 12 | class JointTrajectoryResult : public ros::Msg 13 | { 14 | public: 15 | 16 | JointTrajectoryResult() 17 | { 18 | } 19 | 20 | virtual int serialize(unsigned char *outbuffer) const 21 | { 22 | int offset = 0; 23 | return offset; 24 | } 25 | 26 | virtual int deserialize(unsigned char *inbuffer) 27 | { 28 | int offset = 0; 29 | return offset; 30 | } 31 | 32 | const char * getType(){ return "control_msgs/JointTrajectoryResult"; }; 33 | const char * getMD5(){ return "d41d8cd98f00b204e9800998ecf8427e"; }; 34 | 35 | }; 36 | 37 | } 38 | #endif -------------------------------------------------------------------------------- /docs/setup/ros_lib/control_msgs/PointHeadFeedback.h: -------------------------------------------------------------------------------- 1 | #ifndef _ROS_control_msgs_PointHeadFeedback_h 2 | #define _ROS_control_msgs_PointHeadFeedback_h 3 | 4 | #include 5 | #include 6 | #include 7 | #include "ros/msg.h" 8 | 9 | namespace control_msgs 10 | { 11 | 12 | class PointHeadFeedback : public ros::Msg 13 | { 14 | public: 15 | typedef float _pointing_angle_error_type; 16 | _pointing_angle_error_type pointing_angle_error; 17 | 18 | PointHeadFeedback(): 19 | pointing_angle_error(0) 20 | { 21 | } 22 | 23 | virtual int serialize(unsigned char *outbuffer) const 24 | { 25 | int offset = 0; 26 | offset += serializeAvrFloat64(outbuffer + offset, this->pointing_angle_error); 27 | return offset; 28 | } 29 | 30 | virtual int deserialize(unsigned char *inbuffer) 31 | { 32 | int offset = 0; 33 | offset += deserializeAvrFloat64(inbuffer + offset, &(this->pointing_angle_error)); 34 | return offset; 35 | } 36 | 37 | const char * getType(){ return "control_msgs/PointHeadFeedback"; }; 38 | const char * getMD5(){ return "cce80d27fd763682da8805a73316cab4"; }; 39 | 40 | }; 41 | 42 | } 43 | #endif -------------------------------------------------------------------------------- /docs/setup/ros_lib/control_msgs/PointHeadResult.h: -------------------------------------------------------------------------------- 1 | #ifndef _ROS_control_msgs_PointHeadResult_h 2 | #define _ROS_control_msgs_PointHeadResult_h 3 | 4 | #include 5 | #include 6 | #include 7 | #include "ros/msg.h" 8 | 9 | namespace control_msgs 10 | { 11 | 12 | class PointHeadResult : public ros::Msg 13 | { 14 | public: 15 | 16 | PointHeadResult() 17 | { 18 | } 19 | 20 | virtual int serialize(unsigned char *outbuffer) const 21 | { 22 | int offset = 0; 23 | return offset; 24 | } 25 | 26 | virtual int deserialize(unsigned char *inbuffer) 27 | { 28 | int offset = 0; 29 | return offset; 30 | } 31 | 32 | const char * getType(){ return "control_msgs/PointHeadResult"; }; 33 | const char * getMD5(){ return "d41d8cd98f00b204e9800998ecf8427e"; }; 34 | 35 | }; 36 | 37 | } 38 | #endif -------------------------------------------------------------------------------- /docs/setup/ros_lib/control_msgs/SingleJointPositionResult.h: -------------------------------------------------------------------------------- 1 | #ifndef _ROS_control_msgs_SingleJointPositionResult_h 2 | #define _ROS_control_msgs_SingleJointPositionResult_h 3 | 4 | #include 5 | #include 6 | #include 7 | #include "ros/msg.h" 8 | 9 | namespace control_msgs 10 | { 11 | 12 | class SingleJointPositionResult : public ros::Msg 13 | { 14 | public: 15 | 16 | SingleJointPositionResult() 17 | { 18 | } 19 | 20 | virtual int serialize(unsigned char *outbuffer) const 21 | { 22 | int offset = 0; 23 | return offset; 24 | } 25 | 26 | virtual int deserialize(unsigned char *inbuffer) 27 | { 28 | int offset = 0; 29 | return offset; 30 | } 31 | 32 | const char * getType(){ return "control_msgs/SingleJointPositionResult"; }; 33 | const char * getMD5(){ return "d41d8cd98f00b204e9800998ecf8427e"; }; 34 | 35 | }; 36 | 37 | } 38 | #endif -------------------------------------------------------------------------------- /docs/setup/ros_lib/dynamic_reconfigure/SensorLevels.h: -------------------------------------------------------------------------------- 1 | #ifndef _ROS_dynamic_reconfigure_SensorLevels_h 2 | #define _ROS_dynamic_reconfigure_SensorLevels_h 3 | 4 | #include 5 | #include 6 | #include 7 | #include "ros/msg.h" 8 | 9 | namespace dynamic_reconfigure 10 | { 11 | 12 | class SensorLevels : public ros::Msg 13 | { 14 | public: 15 | enum { RECONFIGURE_CLOSE = 3 }; 16 | enum { RECONFIGURE_STOP = 1 }; 17 | enum { RECONFIGURE_RUNNING = 0 }; 18 | 19 | SensorLevels() 20 | { 21 | } 22 | 23 | virtual int serialize(unsigned char *outbuffer) const 24 | { 25 | int offset = 0; 26 | return offset; 27 | } 28 | 29 | virtual int deserialize(unsigned char *inbuffer) 30 | { 31 | int offset = 0; 32 | return offset; 33 | } 34 | 35 | const char * getType(){ return "dynamic_reconfigure/SensorLevels"; }; 36 | const char * getMD5(){ return "6322637bee96d5489db6e2127c47602c"; }; 37 | 38 | }; 39 | 40 | } 41 | #endif -------------------------------------------------------------------------------- /docs/setup/ros_lib/examples/ADC/ADC.pde: -------------------------------------------------------------------------------- 1 | /* 2 | * rosserial ADC Example 3 | * 4 | * This is a poor man's Oscilloscope. It does not have the sampling 5 | * rate or accuracy of a commerical scope, but it is great to get 6 | * an analog value into ROS in a pinch. 7 | */ 8 | 9 | #if (ARDUINO >= 100) 10 | #include 11 | #else 12 | #include 13 | #endif 14 | #include 15 | #include 16 | 17 | ros::NodeHandle nh; 18 | 19 | rosserial_arduino::Adc adc_msg; 20 | ros::Publisher p("adc", &adc_msg); 21 | 22 | void setup() 23 | { 24 | pinMode(13, OUTPUT); 25 | nh.initNode(); 26 | 27 | nh.advertise(p); 28 | } 29 | 30 | //We average the analog reading to elminate some of the noise 31 | int averageAnalog(int pin){ 32 | int v=0; 33 | for(int i=0; i<4; i++) v+= analogRead(pin); 34 | return v/4; 35 | } 36 | 37 | long adc_timer; 38 | 39 | void loop() 40 | { 41 | adc_msg.adc0 = averageAnalog(0); 42 | adc_msg.adc1 = averageAnalog(1); 43 | adc_msg.adc2 = averageAnalog(2); 44 | adc_msg.adc3 = averageAnalog(3); 45 | adc_msg.adc4 = averageAnalog(4); 46 | adc_msg.adc5 = averageAnalog(5); 47 | 48 | p.publish(&adc_msg); 49 | 50 | nh.spinOnce(); 51 | } 52 | 53 | -------------------------------------------------------------------------------- /docs/setup/ros_lib/examples/Blink/Blink.pde: -------------------------------------------------------------------------------- 1 | /* 2 | * rosserial Subscriber Example 3 | * Blinks an LED on callback 4 | */ 5 | 6 | #include 7 | #include 8 | 9 | ros::NodeHandle nh; 10 | 11 | void messageCb( const std_msgs::Empty& toggle_msg){ 12 | digitalWrite(13, HIGH-digitalRead(13)); // blink the led 13 | } 14 | 15 | ros::Subscriber sub("toggle_led", &messageCb ); 16 | 17 | void setup() 18 | { 19 | pinMode(13, OUTPUT); 20 | nh.initNode(); 21 | nh.subscribe(sub); 22 | } 23 | 24 | void loop() 25 | { 26 | nh.spinOnce(); 27 | delay(1); 28 | } 29 | 30 | -------------------------------------------------------------------------------- /docs/setup/ros_lib/examples/HelloWorld/HelloWorld.pde: -------------------------------------------------------------------------------- 1 | /* 2 | * rosserial Publisher Example 3 | * Prints "hello world!" 4 | */ 5 | 6 | #include 7 | #include 8 | 9 | ros::NodeHandle nh; 10 | 11 | std_msgs::String str_msg; 12 | ros::Publisher chatter("chatter", &str_msg); 13 | 14 | char hello[13] = "hello world!"; 15 | 16 | void setup() 17 | { 18 | nh.initNode(); 19 | nh.advertise(chatter); 20 | } 21 | 22 | void loop() 23 | { 24 | str_msg.data = hello; 25 | chatter.publish( &str_msg ); 26 | nh.spinOnce(); 27 | delay(1000); 28 | } 29 | -------------------------------------------------------------------------------- /docs/setup/ros_lib/examples/Logging/Logging.pde: -------------------------------------------------------------------------------- 1 | /* 2 | * rosserial PubSub Example 3 | * Prints "hello world!" and toggles led 4 | */ 5 | 6 | #include 7 | #include 8 | #include 9 | 10 | ros::NodeHandle nh; 11 | 12 | 13 | std_msgs::String str_msg; 14 | ros::Publisher chatter("chatter", &str_msg); 15 | 16 | char hello[13] = "hello world!"; 17 | 18 | 19 | char debug[]= "debug statements"; 20 | char info[] = "infos"; 21 | char warn[] = "warnings"; 22 | char error[] = "errors"; 23 | char fatal[] = "fatalities"; 24 | 25 | void setup() 26 | { 27 | pinMode(13, OUTPUT); 28 | nh.initNode(); 29 | nh.advertise(chatter); 30 | } 31 | 32 | void loop() 33 | { 34 | str_msg.data = hello; 35 | chatter.publish( &str_msg ); 36 | 37 | nh.logdebug(debug); 38 | nh.loginfo(info); 39 | nh.logwarn(warn); 40 | nh.logerror(error); 41 | nh.logfatal(fatal); 42 | 43 | nh.spinOnce(); 44 | delay(500); 45 | } 46 | -------------------------------------------------------------------------------- /docs/setup/ros_lib/examples/Odom/Odom.pde: -------------------------------------------------------------------------------- 1 | /* 2 | * rosserial Planar Odometry Example 3 | */ 4 | 5 | #include 6 | #include 7 | #include 8 | #include 9 | 10 | ros::NodeHandle nh; 11 | 12 | geometry_msgs::TransformStamped t; 13 | tf::TransformBroadcaster broadcaster; 14 | 15 | double x = 1.0; 16 | double y = 0.0; 17 | double theta = 1.57; 18 | 19 | char base_link[] = "/base_link"; 20 | char odom[] = "/odom"; 21 | 22 | void setup() 23 | { 24 | nh.initNode(); 25 | broadcaster.init(nh); 26 | } 27 | 28 | void loop() 29 | { 30 | // drive in a circle 31 | double dx = 0.2; 32 | double dtheta = 0.18; 33 | x += cos(theta)*dx*0.1; 34 | y += sin(theta)*dx*0.1; 35 | theta += dtheta*0.1; 36 | if(theta > 3.14) 37 | theta=-3.14; 38 | 39 | // tf odom->base_link 40 | t.header.frame_id = odom; 41 | t.child_frame_id = base_link; 42 | 43 | t.transform.translation.x = x; 44 | t.transform.translation.y = y; 45 | 46 | t.transform.rotation = tf::createQuaternionFromYaw(theta); 47 | t.header.stamp = nh.now(); 48 | 49 | broadcaster.sendTransform(t); 50 | nh.spinOnce(); 51 | 52 | delay(10); 53 | } 54 | -------------------------------------------------------------------------------- /docs/setup/ros_lib/examples/ServiceClient/ServiceClient.pde: -------------------------------------------------------------------------------- 1 | /* 2 | * rosserial Service Client 3 | */ 4 | 5 | #include 6 | #include 7 | #include 8 | 9 | ros::NodeHandle nh; 10 | using rosserial_arduino::Test; 11 | 12 | ros::ServiceClient client("test_srv"); 13 | 14 | std_msgs::String str_msg; 15 | ros::Publisher chatter("chatter", &str_msg); 16 | 17 | char hello[13] = "hello world!"; 18 | 19 | void setup() 20 | { 21 | nh.initNode(); 22 | nh.serviceClient(client); 23 | nh.advertise(chatter); 24 | while(!nh.connected()) nh.spinOnce(); 25 | nh.loginfo("Startup complete"); 26 | } 27 | 28 | void loop() 29 | { 30 | Test::Request req; 31 | Test::Response res; 32 | req.input = hello; 33 | client.call(req, res); 34 | str_msg.data = res.output; 35 | chatter.publish( &str_msg ); 36 | nh.spinOnce(); 37 | delay(100); 38 | } 39 | -------------------------------------------------------------------------------- /docs/setup/ros_lib/examples/ServiceClient/client.py: -------------------------------------------------------------------------------- 1 | #!/usr/bin/env python 2 | 3 | """ 4 | Sample code to use with ServiceClient.pde 5 | """ 6 | 7 | import roslib; roslib.load_manifest("rosserial_arduino") 8 | import rospy 9 | 10 | from rosserial_arduino.srv import * 11 | 12 | def callback(req): 13 | print "The arduino is calling! Please send it a message:" 14 | t = TestResponse() 15 | t.output = raw_input() 16 | return t 17 | 18 | rospy.init_node("service_client_test") 19 | rospy.Service("test_srv", Test, callback) 20 | rospy.spin() 21 | -------------------------------------------------------------------------------- /docs/setup/ros_lib/examples/ServiceServer/ServiceServer.pde: -------------------------------------------------------------------------------- 1 | /* 2 | * rosserial Service Server 3 | */ 4 | 5 | #include 6 | #include 7 | #include 8 | 9 | ros::NodeHandle nh; 10 | using rosserial_arduino::Test; 11 | 12 | int i; 13 | void callback(const Test::Request & req, Test::Response & res){ 14 | if((i++)%2) 15 | res.output = "hello"; 16 | else 17 | res.output = "world"; 18 | } 19 | 20 | ros::ServiceServer server("test_srv",&callback); 21 | 22 | std_msgs::String str_msg; 23 | ros::Publisher chatter("chatter", &str_msg); 24 | 25 | char hello[13] = "hello world!"; 26 | 27 | void setup() 28 | { 29 | nh.initNode(); 30 | nh.advertiseService(server); 31 | nh.advertise(chatter); 32 | } 33 | 34 | void loop() 35 | { 36 | str_msg.data = hello; 37 | chatter.publish( &str_msg ); 38 | nh.spinOnce(); 39 | delay(10); 40 | } 41 | -------------------------------------------------------------------------------- /docs/setup/ros_lib/examples/ServoControl/ServoControl.pde: -------------------------------------------------------------------------------- 1 | /* 2 | * rosserial Servo Control Example 3 | * 4 | * This sketch demonstrates the control of hobby R/C servos 5 | * using ROS and the arduiono 6 | * 7 | * For the full tutorial write up, visit 8 | * www.ros.org/wiki/rosserial_arduino_demos 9 | * 10 | * For more information on the Arduino Servo Library 11 | * Checkout : 12 | * http://www.arduino.cc/en/Reference/Servo 13 | */ 14 | 15 | #if (ARDUINO >= 100) 16 | #include 17 | #else 18 | #include 19 | #endif 20 | 21 | #include 22 | #include 23 | #include 24 | 25 | ros::NodeHandle nh; 26 | 27 | Servo servo; 28 | 29 | void servo_cb( const std_msgs::UInt16& cmd_msg){ 30 | servo.write(cmd_msg.data); //set servo angle, should be from 0-180 31 | digitalWrite(13, HIGH-digitalRead(13)); //toggle led 32 | } 33 | 34 | 35 | ros::Subscriber sub("servo", servo_cb); 36 | 37 | void setup(){ 38 | pinMode(13, OUTPUT); 39 | 40 | nh.initNode(); 41 | nh.subscribe(sub); 42 | 43 | servo.attach(9); //attach it to pin 9 44 | } 45 | 46 | void loop(){ 47 | nh.spinOnce(); 48 | delay(1); 49 | } 50 | -------------------------------------------------------------------------------- /docs/setup/ros_lib/examples/TimeTF/TimeTF.pde: -------------------------------------------------------------------------------- 1 | /* 2 | * rosserial Time and TF Example 3 | * Publishes a transform at current time 4 | */ 5 | 6 | #include 7 | #include 8 | #include 9 | 10 | ros::NodeHandle nh; 11 | 12 | geometry_msgs::TransformStamped t; 13 | tf::TransformBroadcaster broadcaster; 14 | 15 | char base_link[] = "/base_link"; 16 | char odom[] = "/odom"; 17 | 18 | void setup() 19 | { 20 | nh.initNode(); 21 | broadcaster.init(nh); 22 | } 23 | 24 | void loop() 25 | { 26 | t.header.frame_id = odom; 27 | t.child_frame_id = base_link; 28 | t.transform.translation.x = 1.0; 29 | t.transform.rotation.x = 0.0; 30 | t.transform.rotation.y = 0.0; 31 | t.transform.rotation.z = 0.0; 32 | t.transform.rotation.w = 1.0; 33 | t.header.stamp = nh.now(); 34 | broadcaster.sendTransform(t); 35 | nh.spinOnce(); 36 | delay(10); 37 | } 38 | -------------------------------------------------------------------------------- /docs/setup/ros_lib/examples/Ultrasound/Ultrasound.pde: -------------------------------------------------------------------------------- 1 | /* 2 | * rosserial Ultrasound Example 3 | * 4 | * This example is for the Maxbotix Ultrasound rangers. 5 | */ 6 | 7 | #include 8 | #include 9 | #include 10 | 11 | ros::NodeHandle nh; 12 | 13 | sensor_msgs::Range range_msg; 14 | ros::Publisher pub_range( "/ultrasound", &range_msg); 15 | 16 | const int adc_pin = 0; 17 | 18 | char frameid[] = "/ultrasound"; 19 | 20 | float getRange_Ultrasound(int pin_num){ 21 | int val = 0; 22 | for(int i=0; i<4; i++) val += analogRead(pin_num); 23 | float range = val; 24 | return range /322.519685; // (0.0124023437 /4) ; //cvt to meters 25 | } 26 | 27 | void setup() 28 | { 29 | nh.initNode(); 30 | nh.advertise(pub_range); 31 | 32 | 33 | range_msg.radiation_type = sensor_msgs::Range::ULTRASOUND; 34 | range_msg.header.frame_id = frameid; 35 | range_msg.field_of_view = 0.1; // fake 36 | range_msg.min_range = 0.0; 37 | range_msg.max_range = 6.47; 38 | 39 | pinMode(8,OUTPUT); 40 | digitalWrite(8, LOW); 41 | } 42 | 43 | 44 | long range_time; 45 | 46 | void loop() 47 | { 48 | 49 | //publish the adc value every 50 milliseconds 50 | //since it takes that long for the sensor to stablize 51 | if ( millis() >= range_time ){ 52 | int r =0; 53 | 54 | range_msg.range = getRange_Ultrasound(5); 55 | range_msg.header.stamp = nh.now(); 56 | pub_range.publish(&range_msg); 57 | range_time = millis() + 50; 58 | } 59 | 60 | nh.spinOnce(); 61 | } 62 | -------------------------------------------------------------------------------- /docs/setup/ros_lib/examples/button_example/button_example.pde: -------------------------------------------------------------------------------- 1 | /* 2 | * Button Example for Rosserial 3 | */ 4 | 5 | #include 6 | #include 7 | 8 | 9 | ros::NodeHandle nh; 10 | 11 | std_msgs::Bool pushed_msg; 12 | ros::Publisher pub_button("pushed", &pushed_msg); 13 | 14 | const int button_pin = 7; 15 | const int led_pin = 13; 16 | 17 | bool last_reading; 18 | long last_debounce_time=0; 19 | long debounce_delay=50; 20 | bool published = true; 21 | 22 | void setup() 23 | { 24 | nh.initNode(); 25 | nh.advertise(pub_button); 26 | 27 | //initialize an LED output pin 28 | //and a input pin for our push button 29 | pinMode(led_pin, OUTPUT); 30 | pinMode(button_pin, INPUT); 31 | 32 | //Enable the pullup resistor on the button 33 | digitalWrite(button_pin, HIGH); 34 | 35 | //The button is a normally button 36 | last_reading = ! digitalRead(button_pin); 37 | 38 | } 39 | 40 | void loop() 41 | { 42 | 43 | bool reading = ! digitalRead(button_pin); 44 | 45 | if (last_reading!= reading){ 46 | last_debounce_time = millis(); 47 | published = false; 48 | } 49 | 50 | //if the button value has not changed for the debounce delay, we know its stable 51 | if ( !published && (millis() - last_debounce_time) > debounce_delay) { 52 | digitalWrite(led_pin, reading); 53 | pushed_msg.data = reading; 54 | pub_button.publish(&pushed_msg); 55 | published = true; 56 | } 57 | 58 | last_reading = reading; 59 | 60 | nh.spinOnce(); 61 | } 62 | -------------------------------------------------------------------------------- /docs/setup/ros_lib/examples/pubsub/pubsub.pde: -------------------------------------------------------------------------------- 1 | /* 2 | * rosserial PubSub Example 3 | * Prints "hello world!" and toggles led 4 | */ 5 | 6 | #include 7 | #include 8 | #include 9 | 10 | ros::NodeHandle nh; 11 | 12 | 13 | void messageCb( const std_msgs::Empty& toggle_msg){ 14 | digitalWrite(13, HIGH-digitalRead(13)); // blink the led 15 | } 16 | 17 | ros::Subscriber sub("toggle_led", messageCb ); 18 | 19 | 20 | 21 | std_msgs::String str_msg; 22 | ros::Publisher chatter("chatter", &str_msg); 23 | 24 | char hello[13] = "hello world!"; 25 | 26 | void setup() 27 | { 28 | pinMode(13, OUTPUT); 29 | nh.initNode(); 30 | nh.advertise(chatter); 31 | nh.subscribe(sub); 32 | } 33 | 34 | void loop() 35 | { 36 | str_msg.data = hello; 37 | chatter.publish( &str_msg ); 38 | nh.spinOnce(); 39 | delay(500); 40 | } 41 | -------------------------------------------------------------------------------- /docs/setup/ros_lib/geometry_msgs/Accel.h: -------------------------------------------------------------------------------- 1 | #ifndef _ROS_geometry_msgs_Accel_h 2 | #define _ROS_geometry_msgs_Accel_h 3 | 4 | #include 5 | #include 6 | #include 7 | #include "ros/msg.h" 8 | #include "geometry_msgs/Vector3.h" 9 | 10 | namespace geometry_msgs 11 | { 12 | 13 | class Accel : public ros::Msg 14 | { 15 | public: 16 | typedef geometry_msgs::Vector3 _linear_type; 17 | _linear_type linear; 18 | typedef geometry_msgs::Vector3 _angular_type; 19 | _angular_type angular; 20 | 21 | Accel(): 22 | linear(), 23 | angular() 24 | { 25 | } 26 | 27 | virtual int serialize(unsigned char *outbuffer) const 28 | { 29 | int offset = 0; 30 | offset += this->linear.serialize(outbuffer + offset); 31 | offset += this->angular.serialize(outbuffer + offset); 32 | return offset; 33 | } 34 | 35 | virtual int deserialize(unsigned char *inbuffer) 36 | { 37 | int offset = 0; 38 | offset += this->linear.deserialize(inbuffer + offset); 39 | offset += this->angular.deserialize(inbuffer + offset); 40 | return offset; 41 | } 42 | 43 | const char * getType(){ return "geometry_msgs/Accel"; }; 44 | const char * getMD5(){ return "9f195f881246fdfa2798d1d3eebca84a"; }; 45 | 46 | }; 47 | 48 | } 49 | #endif -------------------------------------------------------------------------------- /docs/setup/ros_lib/geometry_msgs/AccelStamped.h: -------------------------------------------------------------------------------- 1 | #ifndef _ROS_geometry_msgs_AccelStamped_h 2 | #define _ROS_geometry_msgs_AccelStamped_h 3 | 4 | #include 5 | #include 6 | #include 7 | #include "ros/msg.h" 8 | #include "std_msgs/Header.h" 9 | #include "geometry_msgs/Accel.h" 10 | 11 | namespace geometry_msgs 12 | { 13 | 14 | class AccelStamped : public ros::Msg 15 | { 16 | public: 17 | typedef std_msgs::Header _header_type; 18 | _header_type header; 19 | typedef geometry_msgs::Accel _accel_type; 20 | _accel_type accel; 21 | 22 | AccelStamped(): 23 | header(), 24 | accel() 25 | { 26 | } 27 | 28 | virtual int serialize(unsigned char *outbuffer) const 29 | { 30 | int offset = 0; 31 | offset += this->header.serialize(outbuffer + offset); 32 | offset += this->accel.serialize(outbuffer + offset); 33 | return offset; 34 | } 35 | 36 | virtual int deserialize(unsigned char *inbuffer) 37 | { 38 | int offset = 0; 39 | offset += this->header.deserialize(inbuffer + offset); 40 | offset += this->accel.deserialize(inbuffer + offset); 41 | return offset; 42 | } 43 | 44 | const char * getType(){ return "geometry_msgs/AccelStamped"; }; 45 | const char * getMD5(){ return "d8a98a5d81351b6eb0578c78557e7659"; }; 46 | 47 | }; 48 | 49 | } 50 | #endif -------------------------------------------------------------------------------- /docs/setup/ros_lib/geometry_msgs/AccelWithCovariance.h: -------------------------------------------------------------------------------- 1 | #ifndef _ROS_geometry_msgs_AccelWithCovariance_h 2 | #define _ROS_geometry_msgs_AccelWithCovariance_h 3 | 4 | #include 5 | #include 6 | #include 7 | #include "ros/msg.h" 8 | #include "geometry_msgs/Accel.h" 9 | 10 | namespace geometry_msgs 11 | { 12 | 13 | class AccelWithCovariance : public ros::Msg 14 | { 15 | public: 16 | typedef geometry_msgs::Accel _accel_type; 17 | _accel_type accel; 18 | float covariance[36]; 19 | 20 | AccelWithCovariance(): 21 | accel(), 22 | covariance() 23 | { 24 | } 25 | 26 | virtual int serialize(unsigned char *outbuffer) const 27 | { 28 | int offset = 0; 29 | offset += this->accel.serialize(outbuffer + offset); 30 | for( uint32_t i = 0; i < 36; i++){ 31 | offset += serializeAvrFloat64(outbuffer + offset, this->covariance[i]); 32 | } 33 | return offset; 34 | } 35 | 36 | virtual int deserialize(unsigned char *inbuffer) 37 | { 38 | int offset = 0; 39 | offset += this->accel.deserialize(inbuffer + offset); 40 | for( uint32_t i = 0; i < 36; i++){ 41 | offset += deserializeAvrFloat64(inbuffer + offset, &(this->covariance[i])); 42 | } 43 | return offset; 44 | } 45 | 46 | const char * getType(){ return "geometry_msgs/AccelWithCovariance"; }; 47 | const char * getMD5(){ return "ad5a718d699c6be72a02b8d6a139f334"; }; 48 | 49 | }; 50 | 51 | } 52 | #endif -------------------------------------------------------------------------------- /docs/setup/ros_lib/geometry_msgs/AccelWithCovarianceStamped.h: -------------------------------------------------------------------------------- 1 | #ifndef _ROS_geometry_msgs_AccelWithCovarianceStamped_h 2 | #define _ROS_geometry_msgs_AccelWithCovarianceStamped_h 3 | 4 | #include 5 | #include 6 | #include 7 | #include "ros/msg.h" 8 | #include "std_msgs/Header.h" 9 | #include "geometry_msgs/AccelWithCovariance.h" 10 | 11 | namespace geometry_msgs 12 | { 13 | 14 | class AccelWithCovarianceStamped : public ros::Msg 15 | { 16 | public: 17 | typedef std_msgs::Header _header_type; 18 | _header_type header; 19 | typedef geometry_msgs::AccelWithCovariance _accel_type; 20 | _accel_type accel; 21 | 22 | AccelWithCovarianceStamped(): 23 | header(), 24 | accel() 25 | { 26 | } 27 | 28 | virtual int serialize(unsigned char *outbuffer) const 29 | { 30 | int offset = 0; 31 | offset += this->header.serialize(outbuffer + offset); 32 | offset += this->accel.serialize(outbuffer + offset); 33 | return offset; 34 | } 35 | 36 | virtual int deserialize(unsigned char *inbuffer) 37 | { 38 | int offset = 0; 39 | offset += this->header.deserialize(inbuffer + offset); 40 | offset += this->accel.deserialize(inbuffer + offset); 41 | return offset; 42 | } 43 | 44 | const char * getType(){ return "geometry_msgs/AccelWithCovarianceStamped"; }; 45 | const char * getMD5(){ return "96adb295225031ec8d57fb4251b0a886"; }; 46 | 47 | }; 48 | 49 | } 50 | #endif -------------------------------------------------------------------------------- /docs/setup/ros_lib/geometry_msgs/InertiaStamped.h: -------------------------------------------------------------------------------- 1 | #ifndef _ROS_geometry_msgs_InertiaStamped_h 2 | #define _ROS_geometry_msgs_InertiaStamped_h 3 | 4 | #include 5 | #include 6 | #include 7 | #include "ros/msg.h" 8 | #include "std_msgs/Header.h" 9 | #include "geometry_msgs/Inertia.h" 10 | 11 | namespace geometry_msgs 12 | { 13 | 14 | class InertiaStamped : public ros::Msg 15 | { 16 | public: 17 | typedef std_msgs::Header _header_type; 18 | _header_type header; 19 | typedef geometry_msgs::Inertia _inertia_type; 20 | _inertia_type inertia; 21 | 22 | InertiaStamped(): 23 | header(), 24 | inertia() 25 | { 26 | } 27 | 28 | virtual int serialize(unsigned char *outbuffer) const 29 | { 30 | int offset = 0; 31 | offset += this->header.serialize(outbuffer + offset); 32 | offset += this->inertia.serialize(outbuffer + offset); 33 | return offset; 34 | } 35 | 36 | virtual int deserialize(unsigned char *inbuffer) 37 | { 38 | int offset = 0; 39 | offset += this->header.deserialize(inbuffer + offset); 40 | offset += this->inertia.deserialize(inbuffer + offset); 41 | return offset; 42 | } 43 | 44 | const char * getType(){ return "geometry_msgs/InertiaStamped"; }; 45 | const char * getMD5(){ return "ddee48caeab5a966c5e8d166654a9ac7"; }; 46 | 47 | }; 48 | 49 | } 50 | #endif -------------------------------------------------------------------------------- /docs/setup/ros_lib/geometry_msgs/Point.h: -------------------------------------------------------------------------------- 1 | #ifndef _ROS_geometry_msgs_Point_h 2 | #define _ROS_geometry_msgs_Point_h 3 | 4 | #include 5 | #include 6 | #include 7 | #include "ros/msg.h" 8 | 9 | namespace geometry_msgs 10 | { 11 | 12 | class Point : public ros::Msg 13 | { 14 | public: 15 | typedef float _x_type; 16 | _x_type x; 17 | typedef float _y_type; 18 | _y_type y; 19 | typedef float _z_type; 20 | _z_type z; 21 | 22 | Point(): 23 | x(0), 24 | y(0), 25 | z(0) 26 | { 27 | } 28 | 29 | virtual int serialize(unsigned char *outbuffer) const 30 | { 31 | int offset = 0; 32 | offset += serializeAvrFloat64(outbuffer + offset, this->x); 33 | offset += serializeAvrFloat64(outbuffer + offset, this->y); 34 | offset += serializeAvrFloat64(outbuffer + offset, this->z); 35 | return offset; 36 | } 37 | 38 | virtual int deserialize(unsigned char *inbuffer) 39 | { 40 | int offset = 0; 41 | offset += deserializeAvrFloat64(inbuffer + offset, &(this->x)); 42 | offset += deserializeAvrFloat64(inbuffer + offset, &(this->y)); 43 | offset += deserializeAvrFloat64(inbuffer + offset, &(this->z)); 44 | return offset; 45 | } 46 | 47 | const char * getType(){ return "geometry_msgs/Point"; }; 48 | const char * getMD5(){ return "4a842b65f413084dc2b10fb484ea7f17"; }; 49 | 50 | }; 51 | 52 | } 53 | #endif -------------------------------------------------------------------------------- /docs/setup/ros_lib/geometry_msgs/PointStamped.h: -------------------------------------------------------------------------------- 1 | #ifndef _ROS_geometry_msgs_PointStamped_h 2 | #define _ROS_geometry_msgs_PointStamped_h 3 | 4 | #include 5 | #include 6 | #include 7 | #include "ros/msg.h" 8 | #include "std_msgs/Header.h" 9 | #include "geometry_msgs/Point.h" 10 | 11 | namespace geometry_msgs 12 | { 13 | 14 | class PointStamped : public ros::Msg 15 | { 16 | public: 17 | typedef std_msgs::Header _header_type; 18 | _header_type header; 19 | typedef geometry_msgs::Point _point_type; 20 | _point_type point; 21 | 22 | PointStamped(): 23 | header(), 24 | point() 25 | { 26 | } 27 | 28 | virtual int serialize(unsigned char *outbuffer) const 29 | { 30 | int offset = 0; 31 | offset += this->header.serialize(outbuffer + offset); 32 | offset += this->point.serialize(outbuffer + offset); 33 | return offset; 34 | } 35 | 36 | virtual int deserialize(unsigned char *inbuffer) 37 | { 38 | int offset = 0; 39 | offset += this->header.deserialize(inbuffer + offset); 40 | offset += this->point.deserialize(inbuffer + offset); 41 | return offset; 42 | } 43 | 44 | const char * getType(){ return "geometry_msgs/PointStamped"; }; 45 | const char * getMD5(){ return "c63aecb41bfdfd6b7e1fac37c7cbe7bf"; }; 46 | 47 | }; 48 | 49 | } 50 | #endif -------------------------------------------------------------------------------- /docs/setup/ros_lib/geometry_msgs/PolygonStamped.h: -------------------------------------------------------------------------------- 1 | #ifndef _ROS_geometry_msgs_PolygonStamped_h 2 | #define _ROS_geometry_msgs_PolygonStamped_h 3 | 4 | #include 5 | #include 6 | #include 7 | #include "ros/msg.h" 8 | #include "std_msgs/Header.h" 9 | #include "geometry_msgs/Polygon.h" 10 | 11 | namespace geometry_msgs 12 | { 13 | 14 | class PolygonStamped : public ros::Msg 15 | { 16 | public: 17 | typedef std_msgs::Header _header_type; 18 | _header_type header; 19 | typedef geometry_msgs::Polygon _polygon_type; 20 | _polygon_type polygon; 21 | 22 | PolygonStamped(): 23 | header(), 24 | polygon() 25 | { 26 | } 27 | 28 | virtual int serialize(unsigned char *outbuffer) const 29 | { 30 | int offset = 0; 31 | offset += this->header.serialize(outbuffer + offset); 32 | offset += this->polygon.serialize(outbuffer + offset); 33 | return offset; 34 | } 35 | 36 | virtual int deserialize(unsigned char *inbuffer) 37 | { 38 | int offset = 0; 39 | offset += this->header.deserialize(inbuffer + offset); 40 | offset += this->polygon.deserialize(inbuffer + offset); 41 | return offset; 42 | } 43 | 44 | const char * getType(){ return "geometry_msgs/PolygonStamped"; }; 45 | const char * getMD5(){ return "c6be8f7dc3bee7fe9e8d296070f53340"; }; 46 | 47 | }; 48 | 49 | } 50 | #endif -------------------------------------------------------------------------------- /docs/setup/ros_lib/geometry_msgs/Pose.h: -------------------------------------------------------------------------------- 1 | #ifndef _ROS_geometry_msgs_Pose_h 2 | #define _ROS_geometry_msgs_Pose_h 3 | 4 | #include 5 | #include 6 | #include 7 | #include "ros/msg.h" 8 | #include "geometry_msgs/Point.h" 9 | #include "geometry_msgs/Quaternion.h" 10 | 11 | namespace geometry_msgs 12 | { 13 | 14 | class Pose : public ros::Msg 15 | { 16 | public: 17 | typedef geometry_msgs::Point _position_type; 18 | _position_type position; 19 | typedef geometry_msgs::Quaternion _orientation_type; 20 | _orientation_type orientation; 21 | 22 | Pose(): 23 | position(), 24 | orientation() 25 | { 26 | } 27 | 28 | virtual int serialize(unsigned char *outbuffer) const 29 | { 30 | int offset = 0; 31 | offset += this->position.serialize(outbuffer + offset); 32 | offset += this->orientation.serialize(outbuffer + offset); 33 | return offset; 34 | } 35 | 36 | virtual int deserialize(unsigned char *inbuffer) 37 | { 38 | int offset = 0; 39 | offset += this->position.deserialize(inbuffer + offset); 40 | offset += this->orientation.deserialize(inbuffer + offset); 41 | return offset; 42 | } 43 | 44 | const char * getType(){ return "geometry_msgs/Pose"; }; 45 | const char * getMD5(){ return "e45d45a5a1ce597b249e23fb30fc871f"; }; 46 | 47 | }; 48 | 49 | } 50 | #endif -------------------------------------------------------------------------------- /docs/setup/ros_lib/geometry_msgs/Pose2D.h: -------------------------------------------------------------------------------- 1 | #ifndef _ROS_geometry_msgs_Pose2D_h 2 | #define _ROS_geometry_msgs_Pose2D_h 3 | 4 | #include 5 | #include 6 | #include 7 | #include "ros/msg.h" 8 | 9 | namespace geometry_msgs 10 | { 11 | 12 | class Pose2D : public ros::Msg 13 | { 14 | public: 15 | typedef float _x_type; 16 | _x_type x; 17 | typedef float _y_type; 18 | _y_type y; 19 | typedef float _theta_type; 20 | _theta_type theta; 21 | 22 | Pose2D(): 23 | x(0), 24 | y(0), 25 | theta(0) 26 | { 27 | } 28 | 29 | virtual int serialize(unsigned char *outbuffer) const 30 | { 31 | int offset = 0; 32 | offset += serializeAvrFloat64(outbuffer + offset, this->x); 33 | offset += serializeAvrFloat64(outbuffer + offset, this->y); 34 | offset += serializeAvrFloat64(outbuffer + offset, this->theta); 35 | return offset; 36 | } 37 | 38 | virtual int deserialize(unsigned char *inbuffer) 39 | { 40 | int offset = 0; 41 | offset += deserializeAvrFloat64(inbuffer + offset, &(this->x)); 42 | offset += deserializeAvrFloat64(inbuffer + offset, &(this->y)); 43 | offset += deserializeAvrFloat64(inbuffer + offset, &(this->theta)); 44 | return offset; 45 | } 46 | 47 | const char * getType(){ return "geometry_msgs/Pose2D"; }; 48 | const char * getMD5(){ return "938fa65709584ad8e77d238529be13b8"; }; 49 | 50 | }; 51 | 52 | } 53 | #endif -------------------------------------------------------------------------------- /docs/setup/ros_lib/geometry_msgs/PoseStamped.h: -------------------------------------------------------------------------------- 1 | #ifndef _ROS_geometry_msgs_PoseStamped_h 2 | #define _ROS_geometry_msgs_PoseStamped_h 3 | 4 | #include 5 | #include 6 | #include 7 | #include "ros/msg.h" 8 | #include "std_msgs/Header.h" 9 | #include "geometry_msgs/Pose.h" 10 | 11 | namespace geometry_msgs 12 | { 13 | 14 | class PoseStamped : public ros::Msg 15 | { 16 | public: 17 | typedef std_msgs::Header _header_type; 18 | _header_type header; 19 | typedef geometry_msgs::Pose _pose_type; 20 | _pose_type pose; 21 | 22 | PoseStamped(): 23 | header(), 24 | pose() 25 | { 26 | } 27 | 28 | virtual int serialize(unsigned char *outbuffer) const 29 | { 30 | int offset = 0; 31 | offset += this->header.serialize(outbuffer + offset); 32 | offset += this->pose.serialize(outbuffer + offset); 33 | return offset; 34 | } 35 | 36 | virtual int deserialize(unsigned char *inbuffer) 37 | { 38 | int offset = 0; 39 | offset += this->header.deserialize(inbuffer + offset); 40 | offset += this->pose.deserialize(inbuffer + offset); 41 | return offset; 42 | } 43 | 44 | const char * getType(){ return "geometry_msgs/PoseStamped"; }; 45 | const char * getMD5(){ return "d3812c3cbc69362b77dc0b19b345f8f5"; }; 46 | 47 | }; 48 | 49 | } 50 | #endif -------------------------------------------------------------------------------- /docs/setup/ros_lib/geometry_msgs/PoseWithCovariance.h: -------------------------------------------------------------------------------- 1 | #ifndef _ROS_geometry_msgs_PoseWithCovariance_h 2 | #define _ROS_geometry_msgs_PoseWithCovariance_h 3 | 4 | #include 5 | #include 6 | #include 7 | #include "ros/msg.h" 8 | #include "geometry_msgs/Pose.h" 9 | 10 | namespace geometry_msgs 11 | { 12 | 13 | class PoseWithCovariance : public ros::Msg 14 | { 15 | public: 16 | typedef geometry_msgs::Pose _pose_type; 17 | _pose_type pose; 18 | float covariance[36]; 19 | 20 | PoseWithCovariance(): 21 | pose(), 22 | covariance() 23 | { 24 | } 25 | 26 | virtual int serialize(unsigned char *outbuffer) const 27 | { 28 | int offset = 0; 29 | offset += this->pose.serialize(outbuffer + offset); 30 | for( uint32_t i = 0; i < 36; i++){ 31 | offset += serializeAvrFloat64(outbuffer + offset, this->covariance[i]); 32 | } 33 | return offset; 34 | } 35 | 36 | virtual int deserialize(unsigned char *inbuffer) 37 | { 38 | int offset = 0; 39 | offset += this->pose.deserialize(inbuffer + offset); 40 | for( uint32_t i = 0; i < 36; i++){ 41 | offset += deserializeAvrFloat64(inbuffer + offset, &(this->covariance[i])); 42 | } 43 | return offset; 44 | } 45 | 46 | const char * getType(){ return "geometry_msgs/PoseWithCovariance"; }; 47 | const char * getMD5(){ return "c23e848cf1b7533a8d7c259073a97e6f"; }; 48 | 49 | }; 50 | 51 | } 52 | #endif -------------------------------------------------------------------------------- /docs/setup/ros_lib/geometry_msgs/PoseWithCovarianceStamped.h: -------------------------------------------------------------------------------- 1 | #ifndef _ROS_geometry_msgs_PoseWithCovarianceStamped_h 2 | #define _ROS_geometry_msgs_PoseWithCovarianceStamped_h 3 | 4 | #include 5 | #include 6 | #include 7 | #include "ros/msg.h" 8 | #include "std_msgs/Header.h" 9 | #include "geometry_msgs/PoseWithCovariance.h" 10 | 11 | namespace geometry_msgs 12 | { 13 | 14 | class PoseWithCovarianceStamped : public ros::Msg 15 | { 16 | public: 17 | typedef std_msgs::Header _header_type; 18 | _header_type header; 19 | typedef geometry_msgs::PoseWithCovariance _pose_type; 20 | _pose_type pose; 21 | 22 | PoseWithCovarianceStamped(): 23 | header(), 24 | pose() 25 | { 26 | } 27 | 28 | virtual int serialize(unsigned char *outbuffer) const 29 | { 30 | int offset = 0; 31 | offset += this->header.serialize(outbuffer + offset); 32 | offset += this->pose.serialize(outbuffer + offset); 33 | return offset; 34 | } 35 | 36 | virtual int deserialize(unsigned char *inbuffer) 37 | { 38 | int offset = 0; 39 | offset += this->header.deserialize(inbuffer + offset); 40 | offset += this->pose.deserialize(inbuffer + offset); 41 | return offset; 42 | } 43 | 44 | const char * getType(){ return "geometry_msgs/PoseWithCovarianceStamped"; }; 45 | const char * getMD5(){ return "953b798c0f514ff060a53a3498ce6246"; }; 46 | 47 | }; 48 | 49 | } 50 | #endif -------------------------------------------------------------------------------- /docs/setup/ros_lib/geometry_msgs/QuaternionStamped.h: -------------------------------------------------------------------------------- 1 | #ifndef _ROS_geometry_msgs_QuaternionStamped_h 2 | #define _ROS_geometry_msgs_QuaternionStamped_h 3 | 4 | #include 5 | #include 6 | #include 7 | #include "ros/msg.h" 8 | #include "std_msgs/Header.h" 9 | #include "geometry_msgs/Quaternion.h" 10 | 11 | namespace geometry_msgs 12 | { 13 | 14 | class QuaternionStamped : public ros::Msg 15 | { 16 | public: 17 | typedef std_msgs::Header _header_type; 18 | _header_type header; 19 | typedef geometry_msgs::Quaternion _quaternion_type; 20 | _quaternion_type quaternion; 21 | 22 | QuaternionStamped(): 23 | header(), 24 | quaternion() 25 | { 26 | } 27 | 28 | virtual int serialize(unsigned char *outbuffer) const 29 | { 30 | int offset = 0; 31 | offset += this->header.serialize(outbuffer + offset); 32 | offset += this->quaternion.serialize(outbuffer + offset); 33 | return offset; 34 | } 35 | 36 | virtual int deserialize(unsigned char *inbuffer) 37 | { 38 | int offset = 0; 39 | offset += this->header.deserialize(inbuffer + offset); 40 | offset += this->quaternion.deserialize(inbuffer + offset); 41 | return offset; 42 | } 43 | 44 | const char * getType(){ return "geometry_msgs/QuaternionStamped"; }; 45 | const char * getMD5(){ return "e57f1e547e0e1fd13504588ffc8334e2"; }; 46 | 47 | }; 48 | 49 | } 50 | #endif -------------------------------------------------------------------------------- /docs/setup/ros_lib/geometry_msgs/Transform.h: -------------------------------------------------------------------------------- 1 | #ifndef _ROS_geometry_msgs_Transform_h 2 | #define _ROS_geometry_msgs_Transform_h 3 | 4 | #include 5 | #include 6 | #include 7 | #include "ros/msg.h" 8 | #include "geometry_msgs/Vector3.h" 9 | #include "geometry_msgs/Quaternion.h" 10 | 11 | namespace geometry_msgs 12 | { 13 | 14 | class Transform : public ros::Msg 15 | { 16 | public: 17 | typedef geometry_msgs::Vector3 _translation_type; 18 | _translation_type translation; 19 | typedef geometry_msgs::Quaternion _rotation_type; 20 | _rotation_type rotation; 21 | 22 | Transform(): 23 | translation(), 24 | rotation() 25 | { 26 | } 27 | 28 | virtual int serialize(unsigned char *outbuffer) const 29 | { 30 | int offset = 0; 31 | offset += this->translation.serialize(outbuffer + offset); 32 | offset += this->rotation.serialize(outbuffer + offset); 33 | return offset; 34 | } 35 | 36 | virtual int deserialize(unsigned char *inbuffer) 37 | { 38 | int offset = 0; 39 | offset += this->translation.deserialize(inbuffer + offset); 40 | offset += this->rotation.deserialize(inbuffer + offset); 41 | return offset; 42 | } 43 | 44 | const char * getType(){ return "geometry_msgs/Transform"; }; 45 | const char * getMD5(){ return "ac9eff44abf714214112b05d54a3cf9b"; }; 46 | 47 | }; 48 | 49 | } 50 | #endif -------------------------------------------------------------------------------- /docs/setup/ros_lib/geometry_msgs/Twist.h: -------------------------------------------------------------------------------- 1 | #ifndef _ROS_geometry_msgs_Twist_h 2 | #define _ROS_geometry_msgs_Twist_h 3 | 4 | #include 5 | #include 6 | #include 7 | #include "ros/msg.h" 8 | #include "geometry_msgs/Vector3.h" 9 | 10 | namespace geometry_msgs 11 | { 12 | 13 | class Twist : public ros::Msg 14 | { 15 | public: 16 | typedef geometry_msgs::Vector3 _linear_type; 17 | _linear_type linear; 18 | typedef geometry_msgs::Vector3 _angular_type; 19 | _angular_type angular; 20 | 21 | Twist(): 22 | linear(), 23 | angular() 24 | { 25 | } 26 | 27 | virtual int serialize(unsigned char *outbuffer) const 28 | { 29 | int offset = 0; 30 | offset += this->linear.serialize(outbuffer + offset); 31 | offset += this->angular.serialize(outbuffer + offset); 32 | return offset; 33 | } 34 | 35 | virtual int deserialize(unsigned char *inbuffer) 36 | { 37 | int offset = 0; 38 | offset += this->linear.deserialize(inbuffer + offset); 39 | offset += this->angular.deserialize(inbuffer + offset); 40 | return offset; 41 | } 42 | 43 | const char * getType(){ return "geometry_msgs/Twist"; }; 44 | const char * getMD5(){ return "9f195f881246fdfa2798d1d3eebca84a"; }; 45 | 46 | }; 47 | 48 | } 49 | #endif -------------------------------------------------------------------------------- /docs/setup/ros_lib/geometry_msgs/TwistStamped.h: -------------------------------------------------------------------------------- 1 | #ifndef _ROS_geometry_msgs_TwistStamped_h 2 | #define _ROS_geometry_msgs_TwistStamped_h 3 | 4 | #include 5 | #include 6 | #include 7 | #include "ros/msg.h" 8 | #include "std_msgs/Header.h" 9 | #include "geometry_msgs/Twist.h" 10 | 11 | namespace geometry_msgs 12 | { 13 | 14 | class TwistStamped : public ros::Msg 15 | { 16 | public: 17 | typedef std_msgs::Header _header_type; 18 | _header_type header; 19 | typedef geometry_msgs::Twist _twist_type; 20 | _twist_type twist; 21 | 22 | TwistStamped(): 23 | header(), 24 | twist() 25 | { 26 | } 27 | 28 | virtual int serialize(unsigned char *outbuffer) const 29 | { 30 | int offset = 0; 31 | offset += this->header.serialize(outbuffer + offset); 32 | offset += this->twist.serialize(outbuffer + offset); 33 | return offset; 34 | } 35 | 36 | virtual int deserialize(unsigned char *inbuffer) 37 | { 38 | int offset = 0; 39 | offset += this->header.deserialize(inbuffer + offset); 40 | offset += this->twist.deserialize(inbuffer + offset); 41 | return offset; 42 | } 43 | 44 | const char * getType(){ return "geometry_msgs/TwistStamped"; }; 45 | const char * getMD5(){ return "98d34b0043a2093cf9d9345ab6eef12e"; }; 46 | 47 | }; 48 | 49 | } 50 | #endif -------------------------------------------------------------------------------- /docs/setup/ros_lib/geometry_msgs/TwistWithCovariance.h: -------------------------------------------------------------------------------- 1 | #ifndef _ROS_geometry_msgs_TwistWithCovariance_h 2 | #define _ROS_geometry_msgs_TwistWithCovariance_h 3 | 4 | #include 5 | #include 6 | #include 7 | #include "ros/msg.h" 8 | #include "geometry_msgs/Twist.h" 9 | 10 | namespace geometry_msgs 11 | { 12 | 13 | class TwistWithCovariance : public ros::Msg 14 | { 15 | public: 16 | typedef geometry_msgs::Twist _twist_type; 17 | _twist_type twist; 18 | float covariance[36]; 19 | 20 | TwistWithCovariance(): 21 | twist(), 22 | covariance() 23 | { 24 | } 25 | 26 | virtual int serialize(unsigned char *outbuffer) const 27 | { 28 | int offset = 0; 29 | offset += this->twist.serialize(outbuffer + offset); 30 | for( uint32_t i = 0; i < 36; i++){ 31 | offset += serializeAvrFloat64(outbuffer + offset, this->covariance[i]); 32 | } 33 | return offset; 34 | } 35 | 36 | virtual int deserialize(unsigned char *inbuffer) 37 | { 38 | int offset = 0; 39 | offset += this->twist.deserialize(inbuffer + offset); 40 | for( uint32_t i = 0; i < 36; i++){ 41 | offset += deserializeAvrFloat64(inbuffer + offset, &(this->covariance[i])); 42 | } 43 | return offset; 44 | } 45 | 46 | const char * getType(){ return "geometry_msgs/TwistWithCovariance"; }; 47 | const char * getMD5(){ return "1fe8a28e6890a4cc3ae4c3ca5c7d82e6"; }; 48 | 49 | }; 50 | 51 | } 52 | #endif -------------------------------------------------------------------------------- /docs/setup/ros_lib/geometry_msgs/TwistWithCovarianceStamped.h: -------------------------------------------------------------------------------- 1 | #ifndef _ROS_geometry_msgs_TwistWithCovarianceStamped_h 2 | #define _ROS_geometry_msgs_TwistWithCovarianceStamped_h 3 | 4 | #include 5 | #include 6 | #include 7 | #include "ros/msg.h" 8 | #include "std_msgs/Header.h" 9 | #include "geometry_msgs/TwistWithCovariance.h" 10 | 11 | namespace geometry_msgs 12 | { 13 | 14 | class TwistWithCovarianceStamped : public ros::Msg 15 | { 16 | public: 17 | typedef std_msgs::Header _header_type; 18 | _header_type header; 19 | typedef geometry_msgs::TwistWithCovariance _twist_type; 20 | _twist_type twist; 21 | 22 | TwistWithCovarianceStamped(): 23 | header(), 24 | twist() 25 | { 26 | } 27 | 28 | virtual int serialize(unsigned char *outbuffer) const 29 | { 30 | int offset = 0; 31 | offset += this->header.serialize(outbuffer + offset); 32 | offset += this->twist.serialize(outbuffer + offset); 33 | return offset; 34 | } 35 | 36 | virtual int deserialize(unsigned char *inbuffer) 37 | { 38 | int offset = 0; 39 | offset += this->header.deserialize(inbuffer + offset); 40 | offset += this->twist.deserialize(inbuffer + offset); 41 | return offset; 42 | } 43 | 44 | const char * getType(){ return "geometry_msgs/TwistWithCovarianceStamped"; }; 45 | const char * getMD5(){ return "8927a1a12fb2607ceea095b2dc440a96"; }; 46 | 47 | }; 48 | 49 | } 50 | #endif -------------------------------------------------------------------------------- /docs/setup/ros_lib/geometry_msgs/Vector3.h: -------------------------------------------------------------------------------- 1 | #ifndef _ROS_geometry_msgs_Vector3_h 2 | #define _ROS_geometry_msgs_Vector3_h 3 | 4 | #include 5 | #include 6 | #include 7 | #include "ros/msg.h" 8 | 9 | namespace geometry_msgs 10 | { 11 | 12 | class Vector3 : public ros::Msg 13 | { 14 | public: 15 | typedef float _x_type; 16 | _x_type x; 17 | typedef float _y_type; 18 | _y_type y; 19 | typedef float _z_type; 20 | _z_type z; 21 | 22 | Vector3(): 23 | x(0), 24 | y(0), 25 | z(0) 26 | { 27 | } 28 | 29 | virtual int serialize(unsigned char *outbuffer) const 30 | { 31 | int offset = 0; 32 | offset += serializeAvrFloat64(outbuffer + offset, this->x); 33 | offset += serializeAvrFloat64(outbuffer + offset, this->y); 34 | offset += serializeAvrFloat64(outbuffer + offset, this->z); 35 | return offset; 36 | } 37 | 38 | virtual int deserialize(unsigned char *inbuffer) 39 | { 40 | int offset = 0; 41 | offset += deserializeAvrFloat64(inbuffer + offset, &(this->x)); 42 | offset += deserializeAvrFloat64(inbuffer + offset, &(this->y)); 43 | offset += deserializeAvrFloat64(inbuffer + offset, &(this->z)); 44 | return offset; 45 | } 46 | 47 | const char * getType(){ return "geometry_msgs/Vector3"; }; 48 | const char * getMD5(){ return "4a842b65f413084dc2b10fb484ea7f17"; }; 49 | 50 | }; 51 | 52 | } 53 | #endif -------------------------------------------------------------------------------- /docs/setup/ros_lib/geometry_msgs/Vector3Stamped.h: -------------------------------------------------------------------------------- 1 | #ifndef _ROS_geometry_msgs_Vector3Stamped_h 2 | #define _ROS_geometry_msgs_Vector3Stamped_h 3 | 4 | #include 5 | #include 6 | #include 7 | #include "ros/msg.h" 8 | #include "std_msgs/Header.h" 9 | #include "geometry_msgs/Vector3.h" 10 | 11 | namespace geometry_msgs 12 | { 13 | 14 | class Vector3Stamped : public ros::Msg 15 | { 16 | public: 17 | typedef std_msgs::Header _header_type; 18 | _header_type header; 19 | typedef geometry_msgs::Vector3 _vector_type; 20 | _vector_type vector; 21 | 22 | Vector3Stamped(): 23 | header(), 24 | vector() 25 | { 26 | } 27 | 28 | virtual int serialize(unsigned char *outbuffer) const 29 | { 30 | int offset = 0; 31 | offset += this->header.serialize(outbuffer + offset); 32 | offset += this->vector.serialize(outbuffer + offset); 33 | return offset; 34 | } 35 | 36 | virtual int deserialize(unsigned char *inbuffer) 37 | { 38 | int offset = 0; 39 | offset += this->header.deserialize(inbuffer + offset); 40 | offset += this->vector.deserialize(inbuffer + offset); 41 | return offset; 42 | } 43 | 44 | const char * getType(){ return "geometry_msgs/Vector3Stamped"; }; 45 | const char * getMD5(){ return "7b324c7325e683bf02a9b14b01090ec7"; }; 46 | 47 | }; 48 | 49 | } 50 | #endif -------------------------------------------------------------------------------- /docs/setup/ros_lib/geometry_msgs/Wrench.h: -------------------------------------------------------------------------------- 1 | #ifndef _ROS_geometry_msgs_Wrench_h 2 | #define _ROS_geometry_msgs_Wrench_h 3 | 4 | #include 5 | #include 6 | #include 7 | #include "ros/msg.h" 8 | #include "geometry_msgs/Vector3.h" 9 | 10 | namespace geometry_msgs 11 | { 12 | 13 | class Wrench : public ros::Msg 14 | { 15 | public: 16 | typedef geometry_msgs::Vector3 _force_type; 17 | _force_type force; 18 | typedef geometry_msgs::Vector3 _torque_type; 19 | _torque_type torque; 20 | 21 | Wrench(): 22 | force(), 23 | torque() 24 | { 25 | } 26 | 27 | virtual int serialize(unsigned char *outbuffer) const 28 | { 29 | int offset = 0; 30 | offset += this->force.serialize(outbuffer + offset); 31 | offset += this->torque.serialize(outbuffer + offset); 32 | return offset; 33 | } 34 | 35 | virtual int deserialize(unsigned char *inbuffer) 36 | { 37 | int offset = 0; 38 | offset += this->force.deserialize(inbuffer + offset); 39 | offset += this->torque.deserialize(inbuffer + offset); 40 | return offset; 41 | } 42 | 43 | const char * getType(){ return "geometry_msgs/Wrench"; }; 44 | const char * getMD5(){ return "4f539cf138b23283b520fd271b567936"; }; 45 | 46 | }; 47 | 48 | } 49 | #endif -------------------------------------------------------------------------------- /docs/setup/ros_lib/geometry_msgs/WrenchStamped.h: -------------------------------------------------------------------------------- 1 | #ifndef _ROS_geometry_msgs_WrenchStamped_h 2 | #define _ROS_geometry_msgs_WrenchStamped_h 3 | 4 | #include 5 | #include 6 | #include 7 | #include "ros/msg.h" 8 | #include "std_msgs/Header.h" 9 | #include "geometry_msgs/Wrench.h" 10 | 11 | namespace geometry_msgs 12 | { 13 | 14 | class WrenchStamped : public ros::Msg 15 | { 16 | public: 17 | typedef std_msgs::Header _header_type; 18 | _header_type header; 19 | typedef geometry_msgs::Wrench _wrench_type; 20 | _wrench_type wrench; 21 | 22 | WrenchStamped(): 23 | header(), 24 | wrench() 25 | { 26 | } 27 | 28 | virtual int serialize(unsigned char *outbuffer) const 29 | { 30 | int offset = 0; 31 | offset += this->header.serialize(outbuffer + offset); 32 | offset += this->wrench.serialize(outbuffer + offset); 33 | return offset; 34 | } 35 | 36 | virtual int deserialize(unsigned char *inbuffer) 37 | { 38 | int offset = 0; 39 | offset += this->header.deserialize(inbuffer + offset); 40 | offset += this->wrench.deserialize(inbuffer + offset); 41 | return offset; 42 | } 43 | 44 | const char * getType(){ return "geometry_msgs/WrenchStamped"; }; 45 | const char * getMD5(){ return "d78d3cb249ce23087ade7e7d0c40cfa7"; }; 46 | 47 | }; 48 | 49 | } 50 | #endif -------------------------------------------------------------------------------- /docs/setup/ros_lib/jsk_footstep_msgs/ExecFootstepsFeedback.h: -------------------------------------------------------------------------------- 1 | #ifndef _ROS_jsk_footstep_msgs_ExecFootstepsFeedback_h 2 | #define _ROS_jsk_footstep_msgs_ExecFootstepsFeedback_h 3 | 4 | #include 5 | #include 6 | #include 7 | #include "ros/msg.h" 8 | 9 | namespace jsk_footstep_msgs 10 | { 11 | 12 | class ExecFootstepsFeedback : public ros::Msg 13 | { 14 | public: 15 | 16 | ExecFootstepsFeedback() 17 | { 18 | } 19 | 20 | virtual int serialize(unsigned char *outbuffer) const 21 | { 22 | int offset = 0; 23 | return offset; 24 | } 25 | 26 | virtual int deserialize(unsigned char *inbuffer) 27 | { 28 | int offset = 0; 29 | return offset; 30 | } 31 | 32 | const char * getType(){ return "jsk_footstep_msgs/ExecFootstepsFeedback"; }; 33 | const char * getMD5(){ return "d41d8cd98f00b204e9800998ecf8427e"; }; 34 | 35 | }; 36 | 37 | } 38 | #endif -------------------------------------------------------------------------------- /docs/setup/ros_lib/jsk_footstep_msgs/ExecFootstepsGoal.h: -------------------------------------------------------------------------------- 1 | #ifndef _ROS_jsk_footstep_msgs_ExecFootstepsGoal_h 2 | #define _ROS_jsk_footstep_msgs_ExecFootstepsGoal_h 3 | 4 | #include 5 | #include 6 | #include 7 | #include "ros/msg.h" 8 | #include "jsk_footstep_msgs/FootstepArray.h" 9 | 10 | namespace jsk_footstep_msgs 11 | { 12 | 13 | class ExecFootstepsGoal : public ros::Msg 14 | { 15 | public: 16 | typedef jsk_footstep_msgs::FootstepArray _footstep_type; 17 | _footstep_type footstep; 18 | typedef uint8_t _strategy_type; 19 | _strategy_type strategy; 20 | enum { NEW_TARGET = 0 }; 21 | enum { RESUME = 1 }; 22 | 23 | ExecFootstepsGoal(): 24 | footstep(), 25 | strategy(0) 26 | { 27 | } 28 | 29 | virtual int serialize(unsigned char *outbuffer) const 30 | { 31 | int offset = 0; 32 | offset += this->footstep.serialize(outbuffer + offset); 33 | *(outbuffer + offset + 0) = (this->strategy >> (8 * 0)) & 0xFF; 34 | offset += sizeof(this->strategy); 35 | return offset; 36 | } 37 | 38 | virtual int deserialize(unsigned char *inbuffer) 39 | { 40 | int offset = 0; 41 | offset += this->footstep.deserialize(inbuffer + offset); 42 | this->strategy = ((uint8_t) (*(inbuffer + offset))); 43 | offset += sizeof(this->strategy); 44 | return offset; 45 | } 46 | 47 | const char * getType(){ return "jsk_footstep_msgs/ExecFootstepsGoal"; }; 48 | const char * getMD5(){ return "bb8b96be7f0085372e05a467f65017bb"; }; 49 | 50 | }; 51 | 52 | } 53 | #endif -------------------------------------------------------------------------------- /docs/setup/ros_lib/jsk_footstep_msgs/ExecFootstepsResult.h: -------------------------------------------------------------------------------- 1 | #ifndef _ROS_jsk_footstep_msgs_ExecFootstepsResult_h 2 | #define _ROS_jsk_footstep_msgs_ExecFootstepsResult_h 3 | 4 | #include 5 | #include 6 | #include 7 | #include "ros/msg.h" 8 | 9 | namespace jsk_footstep_msgs 10 | { 11 | 12 | class ExecFootstepsResult : public ros::Msg 13 | { 14 | public: 15 | 16 | ExecFootstepsResult() 17 | { 18 | } 19 | 20 | virtual int serialize(unsigned char *outbuffer) const 21 | { 22 | int offset = 0; 23 | return offset; 24 | } 25 | 26 | virtual int deserialize(unsigned char *inbuffer) 27 | { 28 | int offset = 0; 29 | return offset; 30 | } 31 | 32 | const char * getType(){ return "jsk_footstep_msgs/ExecFootstepsResult"; }; 33 | const char * getMD5(){ return "d41d8cd98f00b204e9800998ecf8427e"; }; 34 | 35 | }; 36 | 37 | } 38 | #endif -------------------------------------------------------------------------------- /docs/setup/ros_lib/jsk_footstep_msgs/PlanFootstepsFeedback.h: -------------------------------------------------------------------------------- 1 | #ifndef _ROS_jsk_footstep_msgs_PlanFootstepsFeedback_h 2 | #define _ROS_jsk_footstep_msgs_PlanFootstepsFeedback_h 3 | 4 | #include 5 | #include 6 | #include 7 | #include "ros/msg.h" 8 | #include "jsk_footstep_msgs/FootstepArray.h" 9 | 10 | namespace jsk_footstep_msgs 11 | { 12 | 13 | class PlanFootstepsFeedback : public ros::Msg 14 | { 15 | public: 16 | typedef jsk_footstep_msgs::FootstepArray _feedback_type; 17 | _feedback_type feedback; 18 | 19 | PlanFootstepsFeedback(): 20 | feedback() 21 | { 22 | } 23 | 24 | virtual int serialize(unsigned char *outbuffer) const 25 | { 26 | int offset = 0; 27 | offset += this->feedback.serialize(outbuffer + offset); 28 | return offset; 29 | } 30 | 31 | virtual int deserialize(unsigned char *inbuffer) 32 | { 33 | int offset = 0; 34 | offset += this->feedback.deserialize(inbuffer + offset); 35 | return offset; 36 | } 37 | 38 | const char * getType(){ return "jsk_footstep_msgs/PlanFootstepsFeedback"; }; 39 | const char * getMD5(){ return "5f4757afbf7a130712f963e49c7f5f00"; }; 40 | 41 | }; 42 | 43 | } 44 | #endif -------------------------------------------------------------------------------- /docs/setup/ros_lib/jsk_footstep_msgs/PlanFootstepsResult.h: -------------------------------------------------------------------------------- 1 | #ifndef _ROS_jsk_footstep_msgs_PlanFootstepsResult_h 2 | #define _ROS_jsk_footstep_msgs_PlanFootstepsResult_h 3 | 4 | #include 5 | #include 6 | #include 7 | #include "ros/msg.h" 8 | #include "jsk_footstep_msgs/FootstepArray.h" 9 | 10 | namespace jsk_footstep_msgs 11 | { 12 | 13 | class PlanFootstepsResult : public ros::Msg 14 | { 15 | public: 16 | typedef jsk_footstep_msgs::FootstepArray _result_type; 17 | _result_type result; 18 | 19 | PlanFootstepsResult(): 20 | result() 21 | { 22 | } 23 | 24 | virtual int serialize(unsigned char *outbuffer) const 25 | { 26 | int offset = 0; 27 | offset += this->result.serialize(outbuffer + offset); 28 | return offset; 29 | } 30 | 31 | virtual int deserialize(unsigned char *inbuffer) 32 | { 33 | int offset = 0; 34 | offset += this->result.deserialize(inbuffer + offset); 35 | return offset; 36 | } 37 | 38 | const char * getType(){ return "jsk_footstep_msgs/PlanFootstepsResult"; }; 39 | const char * getMD5(){ return "951c674749b5b8b08d5eba2e3e62aedd"; }; 40 | 41 | }; 42 | 43 | } 44 | #endif -------------------------------------------------------------------------------- /docs/setup/ros_lib/jsk_recognition_msgs/RotatedRectStamped.h: -------------------------------------------------------------------------------- 1 | #ifndef _ROS_jsk_recognition_msgs_RotatedRectStamped_h 2 | #define _ROS_jsk_recognition_msgs_RotatedRectStamped_h 3 | 4 | #include 5 | #include 6 | #include 7 | #include "ros/msg.h" 8 | #include "std_msgs/Header.h" 9 | #include "jsk_recognition_msgs/RotatedRect.h" 10 | 11 | namespace jsk_recognition_msgs 12 | { 13 | 14 | class RotatedRectStamped : public ros::Msg 15 | { 16 | public: 17 | typedef std_msgs::Header _header_type; 18 | _header_type header; 19 | typedef jsk_recognition_msgs::RotatedRect _rect_type; 20 | _rect_type rect; 21 | 22 | RotatedRectStamped(): 23 | header(), 24 | rect() 25 | { 26 | } 27 | 28 | virtual int serialize(unsigned char *outbuffer) const 29 | { 30 | int offset = 0; 31 | offset += this->header.serialize(outbuffer + offset); 32 | offset += this->rect.serialize(outbuffer + offset); 33 | return offset; 34 | } 35 | 36 | virtual int deserialize(unsigned char *inbuffer) 37 | { 38 | int offset = 0; 39 | offset += this->header.deserialize(inbuffer + offset); 40 | offset += this->rect.deserialize(inbuffer + offset); 41 | return offset; 42 | } 43 | 44 | const char * getType(){ return "jsk_recognition_msgs/RotatedRectStamped"; }; 45 | const char * getMD5(){ return "0260299b5425567e14c7b295b58829e9"; }; 46 | 47 | }; 48 | 49 | } 50 | #endif -------------------------------------------------------------------------------- /docs/setup/ros_lib/map_msgs/ProjectedMap.h: -------------------------------------------------------------------------------- 1 | #ifndef _ROS_map_msgs_ProjectedMap_h 2 | #define _ROS_map_msgs_ProjectedMap_h 3 | 4 | #include 5 | #include 6 | #include 7 | #include "ros/msg.h" 8 | #include "nav_msgs/OccupancyGrid.h" 9 | 10 | namespace map_msgs 11 | { 12 | 13 | class ProjectedMap : public ros::Msg 14 | { 15 | public: 16 | typedef nav_msgs::OccupancyGrid _map_type; 17 | _map_type map; 18 | typedef float _min_z_type; 19 | _min_z_type min_z; 20 | typedef float _max_z_type; 21 | _max_z_type max_z; 22 | 23 | ProjectedMap(): 24 | map(), 25 | min_z(0), 26 | max_z(0) 27 | { 28 | } 29 | 30 | virtual int serialize(unsigned char *outbuffer) const 31 | { 32 | int offset = 0; 33 | offset += this->map.serialize(outbuffer + offset); 34 | offset += serializeAvrFloat64(outbuffer + offset, this->min_z); 35 | offset += serializeAvrFloat64(outbuffer + offset, this->max_z); 36 | return offset; 37 | } 38 | 39 | virtual int deserialize(unsigned char *inbuffer) 40 | { 41 | int offset = 0; 42 | offset += this->map.deserialize(inbuffer + offset); 43 | offset += deserializeAvrFloat64(inbuffer + offset, &(this->min_z)); 44 | offset += deserializeAvrFloat64(inbuffer + offset, &(this->max_z)); 45 | return offset; 46 | } 47 | 48 | const char * getType(){ return "map_msgs/ProjectedMap"; }; 49 | const char * getMD5(){ return "7bbe8f96e45089681dc1ea7d023cbfca"; }; 50 | 51 | }; 52 | 53 | } 54 | #endif -------------------------------------------------------------------------------- /docs/setup/ros_lib/moveit_msgs/ExecuteTrajectoryGoal.h: -------------------------------------------------------------------------------- 1 | #ifndef _ROS_moveit_msgs_ExecuteTrajectoryGoal_h 2 | #define _ROS_moveit_msgs_ExecuteTrajectoryGoal_h 3 | 4 | #include 5 | #include 6 | #include 7 | #include "ros/msg.h" 8 | #include "moveit_msgs/RobotTrajectory.h" 9 | 10 | namespace moveit_msgs 11 | { 12 | 13 | class ExecuteTrajectoryGoal : public ros::Msg 14 | { 15 | public: 16 | typedef moveit_msgs::RobotTrajectory _trajectory_type; 17 | _trajectory_type trajectory; 18 | 19 | ExecuteTrajectoryGoal(): 20 | trajectory() 21 | { 22 | } 23 | 24 | virtual int serialize(unsigned char *outbuffer) const 25 | { 26 | int offset = 0; 27 | offset += this->trajectory.serialize(outbuffer + offset); 28 | return offset; 29 | } 30 | 31 | virtual int deserialize(unsigned char *inbuffer) 32 | { 33 | int offset = 0; 34 | offset += this->trajectory.deserialize(inbuffer + offset); 35 | return offset; 36 | } 37 | 38 | const char * getType(){ return "moveit_msgs/ExecuteTrajectoryGoal"; }; 39 | const char * getMD5(){ return "054c09e62210d7faad2f9fffdad07b57"; }; 40 | 41 | }; 42 | 43 | } 44 | #endif -------------------------------------------------------------------------------- /docs/setup/ros_lib/moveit_msgs/ExecuteTrajectoryResult.h: -------------------------------------------------------------------------------- 1 | #ifndef _ROS_moveit_msgs_ExecuteTrajectoryResult_h 2 | #define _ROS_moveit_msgs_ExecuteTrajectoryResult_h 3 | 4 | #include 5 | #include 6 | #include 7 | #include "ros/msg.h" 8 | #include "moveit_msgs/MoveItErrorCodes.h" 9 | 10 | namespace moveit_msgs 11 | { 12 | 13 | class ExecuteTrajectoryResult : public ros::Msg 14 | { 15 | public: 16 | typedef moveit_msgs::MoveItErrorCodes _error_code_type; 17 | _error_code_type error_code; 18 | 19 | ExecuteTrajectoryResult(): 20 | error_code() 21 | { 22 | } 23 | 24 | virtual int serialize(unsigned char *outbuffer) const 25 | { 26 | int offset = 0; 27 | offset += this->error_code.serialize(outbuffer + offset); 28 | return offset; 29 | } 30 | 31 | virtual int deserialize(unsigned char *inbuffer) 32 | { 33 | int offset = 0; 34 | offset += this->error_code.deserialize(inbuffer + offset); 35 | return offset; 36 | } 37 | 38 | const char * getType(){ return "moveit_msgs/ExecuteTrajectoryResult"; }; 39 | const char * getMD5(){ return "1f7ab918f5d0c5312f25263d3d688122"; }; 40 | 41 | }; 42 | 43 | } 44 | #endif -------------------------------------------------------------------------------- /docs/setup/ros_lib/moveit_msgs/MoveGroupFeedback.h: -------------------------------------------------------------------------------- 1 | #ifndef _ROS_moveit_msgs_MoveGroupFeedback_h 2 | #define _ROS_moveit_msgs_MoveGroupFeedback_h 3 | 4 | #include 5 | #include 6 | #include 7 | #include "ros/msg.h" 8 | 9 | namespace moveit_msgs 10 | { 11 | 12 | class MoveGroupFeedback : public ros::Msg 13 | { 14 | public: 15 | typedef const char* _state_type; 16 | _state_type state; 17 | 18 | MoveGroupFeedback(): 19 | state("") 20 | { 21 | } 22 | 23 | virtual int serialize(unsigned char *outbuffer) const 24 | { 25 | int offset = 0; 26 | uint32_t length_state = strlen(this->state); 27 | varToArr(outbuffer + offset, length_state); 28 | offset += 4; 29 | memcpy(outbuffer + offset, this->state, length_state); 30 | offset += length_state; 31 | return offset; 32 | } 33 | 34 | virtual int deserialize(unsigned char *inbuffer) 35 | { 36 | int offset = 0; 37 | uint32_t length_state; 38 | arrToVar(length_state, (inbuffer + offset)); 39 | offset += 4; 40 | for(unsigned int k= offset; k< offset+length_state; ++k){ 41 | inbuffer[k-1]=inbuffer[k]; 42 | } 43 | inbuffer[offset+length_state-1]=0; 44 | this->state = (char *)(inbuffer + offset-1); 45 | offset += length_state; 46 | return offset; 47 | } 48 | 49 | const char * getType(){ return "moveit_msgs/MoveGroupFeedback"; }; 50 | const char * getMD5(){ return "af6d3a99f0fbeb66d3248fa4b3e675fb"; }; 51 | 52 | }; 53 | 54 | } 55 | #endif -------------------------------------------------------------------------------- /docs/setup/ros_lib/moveit_msgs/MoveGroupGoal.h: -------------------------------------------------------------------------------- 1 | #ifndef _ROS_moveit_msgs_MoveGroupGoal_h 2 | #define _ROS_moveit_msgs_MoveGroupGoal_h 3 | 4 | #include 5 | #include 6 | #include 7 | #include "ros/msg.h" 8 | #include "moveit_msgs/MotionPlanRequest.h" 9 | #include "moveit_msgs/PlanningOptions.h" 10 | 11 | namespace moveit_msgs 12 | { 13 | 14 | class MoveGroupGoal : public ros::Msg 15 | { 16 | public: 17 | typedef moveit_msgs::MotionPlanRequest _request_type; 18 | _request_type request; 19 | typedef moveit_msgs::PlanningOptions _planning_options_type; 20 | _planning_options_type planning_options; 21 | 22 | MoveGroupGoal(): 23 | request(), 24 | planning_options() 25 | { 26 | } 27 | 28 | virtual int serialize(unsigned char *outbuffer) const 29 | { 30 | int offset = 0; 31 | offset += this->request.serialize(outbuffer + offset); 32 | offset += this->planning_options.serialize(outbuffer + offset); 33 | return offset; 34 | } 35 | 36 | virtual int deserialize(unsigned char *inbuffer) 37 | { 38 | int offset = 0; 39 | offset += this->request.deserialize(inbuffer + offset); 40 | offset += this->planning_options.deserialize(inbuffer + offset); 41 | return offset; 42 | } 43 | 44 | const char * getType(){ return "moveit_msgs/MoveGroupGoal"; }; 45 | const char * getMD5(){ return "a6de2db49c561a49babce1a8172e8906"; }; 46 | 47 | }; 48 | 49 | } 50 | #endif -------------------------------------------------------------------------------- /docs/setup/ros_lib/moveit_msgs/OrientedBoundingBox.h: -------------------------------------------------------------------------------- 1 | #ifndef _ROS_moveit_msgs_OrientedBoundingBox_h 2 | #define _ROS_moveit_msgs_OrientedBoundingBox_h 3 | 4 | #include 5 | #include 6 | #include 7 | #include "ros/msg.h" 8 | #include "geometry_msgs/Pose.h" 9 | #include "geometry_msgs/Point32.h" 10 | 11 | namespace moveit_msgs 12 | { 13 | 14 | class OrientedBoundingBox : public ros::Msg 15 | { 16 | public: 17 | typedef geometry_msgs::Pose _pose_type; 18 | _pose_type pose; 19 | typedef geometry_msgs::Point32 _extents_type; 20 | _extents_type extents; 21 | 22 | OrientedBoundingBox(): 23 | pose(), 24 | extents() 25 | { 26 | } 27 | 28 | virtual int serialize(unsigned char *outbuffer) const 29 | { 30 | int offset = 0; 31 | offset += this->pose.serialize(outbuffer + offset); 32 | offset += this->extents.serialize(outbuffer + offset); 33 | return offset; 34 | } 35 | 36 | virtual int deserialize(unsigned char *inbuffer) 37 | { 38 | int offset = 0; 39 | offset += this->pose.deserialize(inbuffer + offset); 40 | offset += this->extents.deserialize(inbuffer + offset); 41 | return offset; 42 | } 43 | 44 | const char * getType(){ return "moveit_msgs/OrientedBoundingBox"; }; 45 | const char * getMD5(){ return "da3bd98e7cb14efa4141367a9d886ee7"; }; 46 | 47 | }; 48 | 49 | } 50 | #endif -------------------------------------------------------------------------------- /docs/setup/ros_lib/moveit_msgs/PickupFeedback.h: -------------------------------------------------------------------------------- 1 | #ifndef _ROS_moveit_msgs_PickupFeedback_h 2 | #define _ROS_moveit_msgs_PickupFeedback_h 3 | 4 | #include 5 | #include 6 | #include 7 | #include "ros/msg.h" 8 | 9 | namespace moveit_msgs 10 | { 11 | 12 | class PickupFeedback : public ros::Msg 13 | { 14 | public: 15 | typedef const char* _state_type; 16 | _state_type state; 17 | 18 | PickupFeedback(): 19 | state("") 20 | { 21 | } 22 | 23 | virtual int serialize(unsigned char *outbuffer) const 24 | { 25 | int offset = 0; 26 | uint32_t length_state = strlen(this->state); 27 | varToArr(outbuffer + offset, length_state); 28 | offset += 4; 29 | memcpy(outbuffer + offset, this->state, length_state); 30 | offset += length_state; 31 | return offset; 32 | } 33 | 34 | virtual int deserialize(unsigned char *inbuffer) 35 | { 36 | int offset = 0; 37 | uint32_t length_state; 38 | arrToVar(length_state, (inbuffer + offset)); 39 | offset += 4; 40 | for(unsigned int k= offset; k< offset+length_state; ++k){ 41 | inbuffer[k-1]=inbuffer[k]; 42 | } 43 | inbuffer[offset+length_state-1]=0; 44 | this->state = (char *)(inbuffer + offset-1); 45 | offset += length_state; 46 | return offset; 47 | } 48 | 49 | const char * getType(){ return "moveit_msgs/PickupFeedback"; }; 50 | const char * getMD5(){ return "af6d3a99f0fbeb66d3248fa4b3e675fb"; }; 51 | 52 | }; 53 | 54 | } 55 | #endif -------------------------------------------------------------------------------- /docs/setup/ros_lib/moveit_msgs/PlaceFeedback.h: -------------------------------------------------------------------------------- 1 | #ifndef _ROS_moveit_msgs_PlaceFeedback_h 2 | #define _ROS_moveit_msgs_PlaceFeedback_h 3 | 4 | #include 5 | #include 6 | #include 7 | #include "ros/msg.h" 8 | 9 | namespace moveit_msgs 10 | { 11 | 12 | class PlaceFeedback : public ros::Msg 13 | { 14 | public: 15 | typedef const char* _state_type; 16 | _state_type state; 17 | 18 | PlaceFeedback(): 19 | state("") 20 | { 21 | } 22 | 23 | virtual int serialize(unsigned char *outbuffer) const 24 | { 25 | int offset = 0; 26 | uint32_t length_state = strlen(this->state); 27 | varToArr(outbuffer + offset, length_state); 28 | offset += 4; 29 | memcpy(outbuffer + offset, this->state, length_state); 30 | offset += length_state; 31 | return offset; 32 | } 33 | 34 | virtual int deserialize(unsigned char *inbuffer) 35 | { 36 | int offset = 0; 37 | uint32_t length_state; 38 | arrToVar(length_state, (inbuffer + offset)); 39 | offset += 4; 40 | for(unsigned int k= offset; k< offset+length_state; ++k){ 41 | inbuffer[k-1]=inbuffer[k]; 42 | } 43 | inbuffer[offset+length_state-1]=0; 44 | this->state = (char *)(inbuffer + offset-1); 45 | offset += length_state; 46 | return offset; 47 | } 48 | 49 | const char * getType(){ return "moveit_msgs/PlaceFeedback"; }; 50 | const char * getMD5(){ return "af6d3a99f0fbeb66d3248fa4b3e675fb"; }; 51 | 52 | }; 53 | 54 | } 55 | #endif -------------------------------------------------------------------------------- /docs/setup/ros_lib/nav_msgs/GetMapFeedback.h: -------------------------------------------------------------------------------- 1 | #ifndef _ROS_nav_msgs_GetMapFeedback_h 2 | #define _ROS_nav_msgs_GetMapFeedback_h 3 | 4 | #include 5 | #include 6 | #include 7 | #include "ros/msg.h" 8 | 9 | namespace nav_msgs 10 | { 11 | 12 | class GetMapFeedback : public ros::Msg 13 | { 14 | public: 15 | 16 | GetMapFeedback() 17 | { 18 | } 19 | 20 | virtual int serialize(unsigned char *outbuffer) const 21 | { 22 | int offset = 0; 23 | return offset; 24 | } 25 | 26 | virtual int deserialize(unsigned char *inbuffer) 27 | { 28 | int offset = 0; 29 | return offset; 30 | } 31 | 32 | const char * getType(){ return "nav_msgs/GetMapFeedback"; }; 33 | const char * getMD5(){ return "d41d8cd98f00b204e9800998ecf8427e"; }; 34 | 35 | }; 36 | 37 | } 38 | #endif -------------------------------------------------------------------------------- /docs/setup/ros_lib/nav_msgs/GetMapGoal.h: -------------------------------------------------------------------------------- 1 | #ifndef _ROS_nav_msgs_GetMapGoal_h 2 | #define _ROS_nav_msgs_GetMapGoal_h 3 | 4 | #include 5 | #include 6 | #include 7 | #include "ros/msg.h" 8 | 9 | namespace nav_msgs 10 | { 11 | 12 | class GetMapGoal : public ros::Msg 13 | { 14 | public: 15 | 16 | GetMapGoal() 17 | { 18 | } 19 | 20 | virtual int serialize(unsigned char *outbuffer) const 21 | { 22 | int offset = 0; 23 | return offset; 24 | } 25 | 26 | virtual int deserialize(unsigned char *inbuffer) 27 | { 28 | int offset = 0; 29 | return offset; 30 | } 31 | 32 | const char * getType(){ return "nav_msgs/GetMapGoal"; }; 33 | const char * getMD5(){ return "d41d8cd98f00b204e9800998ecf8427e"; }; 34 | 35 | }; 36 | 37 | } 38 | #endif -------------------------------------------------------------------------------- /docs/setup/ros_lib/nav_msgs/GetMapResult.h: -------------------------------------------------------------------------------- 1 | #ifndef _ROS_nav_msgs_GetMapResult_h 2 | #define _ROS_nav_msgs_GetMapResult_h 3 | 4 | #include 5 | #include 6 | #include 7 | #include "ros/msg.h" 8 | #include "nav_msgs/OccupancyGrid.h" 9 | 10 | namespace nav_msgs 11 | { 12 | 13 | class GetMapResult : public ros::Msg 14 | { 15 | public: 16 | typedef nav_msgs::OccupancyGrid _map_type; 17 | _map_type map; 18 | 19 | GetMapResult(): 20 | map() 21 | { 22 | } 23 | 24 | virtual int serialize(unsigned char *outbuffer) const 25 | { 26 | int offset = 0; 27 | offset += this->map.serialize(outbuffer + offset); 28 | return offset; 29 | } 30 | 31 | virtual int deserialize(unsigned char *inbuffer) 32 | { 33 | int offset = 0; 34 | offset += this->map.deserialize(inbuffer + offset); 35 | return offset; 36 | } 37 | 38 | const char * getType(){ return "nav_msgs/GetMapResult"; }; 39 | const char * getMD5(){ return "6cdd0a18e0aff5b0a3ca2326a89b54ff"; }; 40 | 41 | }; 42 | 43 | } 44 | #endif -------------------------------------------------------------------------------- /docs/setup/ros_lib/object_recognition_msgs/ObjectRecognitionFeedback.h: -------------------------------------------------------------------------------- 1 | #ifndef _ROS_object_recognition_msgs_ObjectRecognitionFeedback_h 2 | #define _ROS_object_recognition_msgs_ObjectRecognitionFeedback_h 3 | 4 | #include 5 | #include 6 | #include 7 | #include "ros/msg.h" 8 | 9 | namespace object_recognition_msgs 10 | { 11 | 12 | class ObjectRecognitionFeedback : public ros::Msg 13 | { 14 | public: 15 | 16 | ObjectRecognitionFeedback() 17 | { 18 | } 19 | 20 | virtual int serialize(unsigned char *outbuffer) const 21 | { 22 | int offset = 0; 23 | return offset; 24 | } 25 | 26 | virtual int deserialize(unsigned char *inbuffer) 27 | { 28 | int offset = 0; 29 | return offset; 30 | } 31 | 32 | const char * getType(){ return "object_recognition_msgs/ObjectRecognitionFeedback"; }; 33 | const char * getMD5(){ return "d41d8cd98f00b204e9800998ecf8427e"; }; 34 | 35 | }; 36 | 37 | } 38 | #endif -------------------------------------------------------------------------------- /docs/setup/ros_lib/object_recognition_msgs/ObjectRecognitionResult.h: -------------------------------------------------------------------------------- 1 | #ifndef _ROS_object_recognition_msgs_ObjectRecognitionResult_h 2 | #define _ROS_object_recognition_msgs_ObjectRecognitionResult_h 3 | 4 | #include 5 | #include 6 | #include 7 | #include "ros/msg.h" 8 | #include "object_recognition_msgs/RecognizedObjectArray.h" 9 | 10 | namespace object_recognition_msgs 11 | { 12 | 13 | class ObjectRecognitionResult : public ros::Msg 14 | { 15 | public: 16 | typedef object_recognition_msgs::RecognizedObjectArray _recognized_objects_type; 17 | _recognized_objects_type recognized_objects; 18 | 19 | ObjectRecognitionResult(): 20 | recognized_objects() 21 | { 22 | } 23 | 24 | virtual int serialize(unsigned char *outbuffer) const 25 | { 26 | int offset = 0; 27 | offset += this->recognized_objects.serialize(outbuffer + offset); 28 | return offset; 29 | } 30 | 31 | virtual int deserialize(unsigned char *inbuffer) 32 | { 33 | int offset = 0; 34 | offset += this->recognized_objects.deserialize(inbuffer + offset); 35 | return offset; 36 | } 37 | 38 | const char * getType(){ return "object_recognition_msgs/ObjectRecognitionResult"; }; 39 | const char * getMD5(){ return "868e41288f9f8636e2b6c51f1af6aa9c"; }; 40 | 41 | }; 42 | 43 | } 44 | #endif -------------------------------------------------------------------------------- /docs/setup/ros_lib/py_trees_msgs/DockGoal.h: -------------------------------------------------------------------------------- 1 | #ifndef _ROS_py_trees_msgs_DockGoal_h 2 | #define _ROS_py_trees_msgs_DockGoal_h 3 | 4 | #include 5 | #include 6 | #include 7 | #include "ros/msg.h" 8 | 9 | namespace py_trees_msgs 10 | { 11 | 12 | class DockGoal : public ros::Msg 13 | { 14 | public: 15 | typedef bool _dock_type; 16 | _dock_type dock; 17 | 18 | DockGoal(): 19 | dock(0) 20 | { 21 | } 22 | 23 | virtual int serialize(unsigned char *outbuffer) const 24 | { 25 | int offset = 0; 26 | union { 27 | bool real; 28 | uint8_t base; 29 | } u_dock; 30 | u_dock.real = this->dock; 31 | *(outbuffer + offset + 0) = (u_dock.base >> (8 * 0)) & 0xFF; 32 | offset += sizeof(this->dock); 33 | return offset; 34 | } 35 | 36 | virtual int deserialize(unsigned char *inbuffer) 37 | { 38 | int offset = 0; 39 | union { 40 | bool real; 41 | uint8_t base; 42 | } u_dock; 43 | u_dock.base = 0; 44 | u_dock.base |= ((uint8_t) (*(inbuffer + offset + 0))) << (8 * 0); 45 | this->dock = u_dock.real; 46 | offset += sizeof(this->dock); 47 | return offset; 48 | } 49 | 50 | const char * getType(){ return "py_trees_msgs/DockGoal"; }; 51 | const char * getMD5(){ return "035360b0bb03f7f742a0b2d734a3a660"; }; 52 | 53 | }; 54 | 55 | } 56 | #endif -------------------------------------------------------------------------------- /docs/setup/ros_lib/py_trees_msgs/RotateGoal.h: -------------------------------------------------------------------------------- 1 | #ifndef _ROS_py_trees_msgs_RotateGoal_h 2 | #define _ROS_py_trees_msgs_RotateGoal_h 3 | 4 | #include 5 | #include 6 | #include 7 | #include "ros/msg.h" 8 | 9 | namespace py_trees_msgs 10 | { 11 | 12 | class RotateGoal : public ros::Msg 13 | { 14 | public: 15 | 16 | RotateGoal() 17 | { 18 | } 19 | 20 | virtual int serialize(unsigned char *outbuffer) const 21 | { 22 | int offset = 0; 23 | return offset; 24 | } 25 | 26 | virtual int deserialize(unsigned char *inbuffer) 27 | { 28 | int offset = 0; 29 | return offset; 30 | } 31 | 32 | const char * getType(){ return "py_trees_msgs/RotateGoal"; }; 33 | const char * getMD5(){ return "d41d8cd98f00b204e9800998ecf8427e"; }; 34 | 35 | }; 36 | 37 | } 38 | #endif -------------------------------------------------------------------------------- /docs/setup/ros_lib/rocon_service_pair_msgs/TestiesPair.h: -------------------------------------------------------------------------------- 1 | #ifndef _ROS_rocon_service_pair_msgs_TestiesPair_h 2 | #define _ROS_rocon_service_pair_msgs_TestiesPair_h 3 | 4 | #include 5 | #include 6 | #include 7 | #include "ros/msg.h" 8 | #include "rocon_service_pair_msgs/TestiesPairRequest.h" 9 | #include "rocon_service_pair_msgs/TestiesPairResponse.h" 10 | 11 | namespace rocon_service_pair_msgs 12 | { 13 | 14 | class TestiesPair : public ros::Msg 15 | { 16 | public: 17 | typedef rocon_service_pair_msgs::TestiesPairRequest _pair_request_type; 18 | _pair_request_type pair_request; 19 | typedef rocon_service_pair_msgs::TestiesPairResponse _pair_response_type; 20 | _pair_response_type pair_response; 21 | 22 | TestiesPair(): 23 | pair_request(), 24 | pair_response() 25 | { 26 | } 27 | 28 | virtual int serialize(unsigned char *outbuffer) const 29 | { 30 | int offset = 0; 31 | offset += this->pair_request.serialize(outbuffer + offset); 32 | offset += this->pair_response.serialize(outbuffer + offset); 33 | return offset; 34 | } 35 | 36 | virtual int deserialize(unsigned char *inbuffer) 37 | { 38 | int offset = 0; 39 | offset += this->pair_request.deserialize(inbuffer + offset); 40 | offset += this->pair_response.deserialize(inbuffer + offset); 41 | return offset; 42 | } 43 | 44 | const char * getType(){ return "rocon_service_pair_msgs/TestiesPair"; }; 45 | const char * getMD5(){ return "7b5cb9b4ccdb74840ce04ea92d2a141d"; }; 46 | 47 | }; 48 | 49 | } 50 | #endif -------------------------------------------------------------------------------- /docs/setup/ros_lib/rocon_service_pair_msgs/TestiesPairRequest.h: -------------------------------------------------------------------------------- 1 | #ifndef _ROS_rocon_service_pair_msgs_TestiesPairRequest_h 2 | #define _ROS_rocon_service_pair_msgs_TestiesPairRequest_h 3 | 4 | #include 5 | #include 6 | #include 7 | #include "ros/msg.h" 8 | #include "uuid_msgs/UniqueID.h" 9 | #include "rocon_service_pair_msgs/TestiesRequest.h" 10 | 11 | namespace rocon_service_pair_msgs 12 | { 13 | 14 | class TestiesPairRequest : public ros::Msg 15 | { 16 | public: 17 | typedef uuid_msgs::UniqueID _id_type; 18 | _id_type id; 19 | typedef rocon_service_pair_msgs::TestiesRequest _request_type; 20 | _request_type request; 21 | 22 | TestiesPairRequest(): 23 | id(), 24 | request() 25 | { 26 | } 27 | 28 | virtual int serialize(unsigned char *outbuffer) const 29 | { 30 | int offset = 0; 31 | offset += this->id.serialize(outbuffer + offset); 32 | offset += this->request.serialize(outbuffer + offset); 33 | return offset; 34 | } 35 | 36 | virtual int deserialize(unsigned char *inbuffer) 37 | { 38 | int offset = 0; 39 | offset += this->id.deserialize(inbuffer + offset); 40 | offset += this->request.deserialize(inbuffer + offset); 41 | return offset; 42 | } 43 | 44 | const char * getType(){ return "rocon_service_pair_msgs/TestiesPairRequest"; }; 45 | const char * getMD5(){ return "71ec95e384ce52aa32491f3b69a62027"; }; 46 | 47 | }; 48 | 49 | } 50 | #endif -------------------------------------------------------------------------------- /docs/setup/ros_lib/rocon_service_pair_msgs/TestiesPairResponse.h: -------------------------------------------------------------------------------- 1 | #ifndef _ROS_rocon_service_pair_msgs_TestiesPairResponse_h 2 | #define _ROS_rocon_service_pair_msgs_TestiesPairResponse_h 3 | 4 | #include 5 | #include 6 | #include 7 | #include "ros/msg.h" 8 | #include "uuid_msgs/UniqueID.h" 9 | #include "rocon_service_pair_msgs/TestiesResponse.h" 10 | 11 | namespace rocon_service_pair_msgs 12 | { 13 | 14 | class TestiesPairResponse : public ros::Msg 15 | { 16 | public: 17 | typedef uuid_msgs::UniqueID _id_type; 18 | _id_type id; 19 | typedef rocon_service_pair_msgs::TestiesResponse _response_type; 20 | _response_type response; 21 | 22 | TestiesPairResponse(): 23 | id(), 24 | response() 25 | { 26 | } 27 | 28 | virtual int serialize(unsigned char *outbuffer) const 29 | { 30 | int offset = 0; 31 | offset += this->id.serialize(outbuffer + offset); 32 | offset += this->response.serialize(outbuffer + offset); 33 | return offset; 34 | } 35 | 36 | virtual int deserialize(unsigned char *inbuffer) 37 | { 38 | int offset = 0; 39 | offset += this->id.deserialize(inbuffer + offset); 40 | offset += this->response.deserialize(inbuffer + offset); 41 | return offset; 42 | } 43 | 44 | const char * getType(){ return "rocon_service_pair_msgs/TestiesPairResponse"; }; 45 | const char * getMD5(){ return "05404c9fe275eda57650fdfced8cf402"; }; 46 | 47 | }; 48 | 49 | } 50 | #endif -------------------------------------------------------------------------------- /docs/setup/ros_lib/rocon_service_pair_msgs/TestiesRequest.h: -------------------------------------------------------------------------------- 1 | #ifndef _ROS_rocon_service_pair_msgs_TestiesRequest_h 2 | #define _ROS_rocon_service_pair_msgs_TestiesRequest_h 3 | 4 | #include 5 | #include 6 | #include 7 | #include "ros/msg.h" 8 | 9 | namespace rocon_service_pair_msgs 10 | { 11 | 12 | class TestiesRequest : public ros::Msg 13 | { 14 | public: 15 | typedef const char* _data_type; 16 | _data_type data; 17 | 18 | TestiesRequest(): 19 | data("") 20 | { 21 | } 22 | 23 | virtual int serialize(unsigned char *outbuffer) const 24 | { 25 | int offset = 0; 26 | uint32_t length_data = strlen(this->data); 27 | varToArr(outbuffer + offset, length_data); 28 | offset += 4; 29 | memcpy(outbuffer + offset, this->data, length_data); 30 | offset += length_data; 31 | return offset; 32 | } 33 | 34 | virtual int deserialize(unsigned char *inbuffer) 35 | { 36 | int offset = 0; 37 | uint32_t length_data; 38 | arrToVar(length_data, (inbuffer + offset)); 39 | offset += 4; 40 | for(unsigned int k= offset; k< offset+length_data; ++k){ 41 | inbuffer[k-1]=inbuffer[k]; 42 | } 43 | inbuffer[offset+length_data-1]=0; 44 | this->data = (char *)(inbuffer + offset-1); 45 | offset += length_data; 46 | return offset; 47 | } 48 | 49 | const char * getType(){ return "rocon_service_pair_msgs/TestiesRequest"; }; 50 | const char * getMD5(){ return "992ce8a1687cec8c8bd883ec73ca41d1"; }; 51 | 52 | }; 53 | 54 | } 55 | #endif -------------------------------------------------------------------------------- /docs/setup/ros_lib/rocon_std_msgs/StringsPair.h: -------------------------------------------------------------------------------- 1 | #ifndef _ROS_rocon_std_msgs_StringsPair_h 2 | #define _ROS_rocon_std_msgs_StringsPair_h 3 | 4 | #include 5 | #include 6 | #include 7 | #include "ros/msg.h" 8 | #include "rocon_std_msgs/StringsPairRequest.h" 9 | #include "rocon_std_msgs/StringsPairResponse.h" 10 | 11 | namespace rocon_std_msgs 12 | { 13 | 14 | class StringsPair : public ros::Msg 15 | { 16 | public: 17 | typedef rocon_std_msgs::StringsPairRequest _pair_request_type; 18 | _pair_request_type pair_request; 19 | typedef rocon_std_msgs::StringsPairResponse _pair_response_type; 20 | _pair_response_type pair_response; 21 | 22 | StringsPair(): 23 | pair_request(), 24 | pair_response() 25 | { 26 | } 27 | 28 | virtual int serialize(unsigned char *outbuffer) const 29 | { 30 | int offset = 0; 31 | offset += this->pair_request.serialize(outbuffer + offset); 32 | offset += this->pair_response.serialize(outbuffer + offset); 33 | return offset; 34 | } 35 | 36 | virtual int deserialize(unsigned char *inbuffer) 37 | { 38 | int offset = 0; 39 | offset += this->pair_request.deserialize(inbuffer + offset); 40 | offset += this->pair_response.deserialize(inbuffer + offset); 41 | return offset; 42 | } 43 | 44 | const char * getType(){ return "rocon_std_msgs/StringsPair"; }; 45 | const char * getMD5(){ return "d41c9071bd514be249c417a13ec83e65"; }; 46 | 47 | }; 48 | 49 | } 50 | #endif -------------------------------------------------------------------------------- /docs/setup/ros_lib/rocon_std_msgs/StringsPairRequest.h: -------------------------------------------------------------------------------- 1 | #ifndef _ROS_rocon_std_msgs_StringsPairRequest_h 2 | #define _ROS_rocon_std_msgs_StringsPairRequest_h 3 | 4 | #include 5 | #include 6 | #include 7 | #include "ros/msg.h" 8 | #include "uuid_msgs/UniqueID.h" 9 | #include "rocon_std_msgs/StringsRequest.h" 10 | 11 | namespace rocon_std_msgs 12 | { 13 | 14 | class StringsPairRequest : public ros::Msg 15 | { 16 | public: 17 | typedef uuid_msgs::UniqueID _id_type; 18 | _id_type id; 19 | typedef rocon_std_msgs::StringsRequest _request_type; 20 | _request_type request; 21 | 22 | StringsPairRequest(): 23 | id(), 24 | request() 25 | { 26 | } 27 | 28 | virtual int serialize(unsigned char *outbuffer) const 29 | { 30 | int offset = 0; 31 | offset += this->id.serialize(outbuffer + offset); 32 | offset += this->request.serialize(outbuffer + offset); 33 | return offset; 34 | } 35 | 36 | virtual int deserialize(unsigned char *inbuffer) 37 | { 38 | int offset = 0; 39 | offset += this->id.deserialize(inbuffer + offset); 40 | offset += this->request.deserialize(inbuffer + offset); 41 | return offset; 42 | } 43 | 44 | const char * getType(){ return "rocon_std_msgs/StringsPairRequest"; }; 45 | const char * getMD5(){ return "71ec95e384ce52aa32491f3b69a62027"; }; 46 | 47 | }; 48 | 49 | } 50 | #endif -------------------------------------------------------------------------------- /docs/setup/ros_lib/rocon_std_msgs/StringsPairResponse.h: -------------------------------------------------------------------------------- 1 | #ifndef _ROS_rocon_std_msgs_StringsPairResponse_h 2 | #define _ROS_rocon_std_msgs_StringsPairResponse_h 3 | 4 | #include 5 | #include 6 | #include 7 | #include "ros/msg.h" 8 | #include "uuid_msgs/UniqueID.h" 9 | #include "rocon_std_msgs/StringsResponse.h" 10 | 11 | namespace rocon_std_msgs 12 | { 13 | 14 | class StringsPairResponse : public ros::Msg 15 | { 16 | public: 17 | typedef uuid_msgs::UniqueID _id_type; 18 | _id_type id; 19 | typedef rocon_std_msgs::StringsResponse _response_type; 20 | _response_type response; 21 | 22 | StringsPairResponse(): 23 | id(), 24 | response() 25 | { 26 | } 27 | 28 | virtual int serialize(unsigned char *outbuffer) const 29 | { 30 | int offset = 0; 31 | offset += this->id.serialize(outbuffer + offset); 32 | offset += this->response.serialize(outbuffer + offset); 33 | return offset; 34 | } 35 | 36 | virtual int deserialize(unsigned char *inbuffer) 37 | { 38 | int offset = 0; 39 | offset += this->id.deserialize(inbuffer + offset); 40 | offset += this->response.deserialize(inbuffer + offset); 41 | return offset; 42 | } 43 | 44 | const char * getType(){ return "rocon_std_msgs/StringsPairResponse"; }; 45 | const char * getMD5(){ return "7b20492548347a7692aa8c5680af8d1b"; }; 46 | 47 | }; 48 | 49 | } 50 | #endif -------------------------------------------------------------------------------- /docs/setup/ros_lib/rocon_std_msgs/StringsRequest.h: -------------------------------------------------------------------------------- 1 | #ifndef _ROS_rocon_std_msgs_StringsRequest_h 2 | #define _ROS_rocon_std_msgs_StringsRequest_h 3 | 4 | #include 5 | #include 6 | #include 7 | #include "ros/msg.h" 8 | 9 | namespace rocon_std_msgs 10 | { 11 | 12 | class StringsRequest : public ros::Msg 13 | { 14 | public: 15 | typedef const char* _data_type; 16 | _data_type data; 17 | 18 | StringsRequest(): 19 | data("") 20 | { 21 | } 22 | 23 | virtual int serialize(unsigned char *outbuffer) const 24 | { 25 | int offset = 0; 26 | uint32_t length_data = strlen(this->data); 27 | varToArr(outbuffer + offset, length_data); 28 | offset += 4; 29 | memcpy(outbuffer + offset, this->data, length_data); 30 | offset += length_data; 31 | return offset; 32 | } 33 | 34 | virtual int deserialize(unsigned char *inbuffer) 35 | { 36 | int offset = 0; 37 | uint32_t length_data; 38 | arrToVar(length_data, (inbuffer + offset)); 39 | offset += 4; 40 | for(unsigned int k= offset; k< offset+length_data; ++k){ 41 | inbuffer[k-1]=inbuffer[k]; 42 | } 43 | inbuffer[offset+length_data-1]=0; 44 | this->data = (char *)(inbuffer + offset-1); 45 | offset += length_data; 46 | return offset; 47 | } 48 | 49 | const char * getType(){ return "rocon_std_msgs/StringsRequest"; }; 50 | const char * getMD5(){ return "992ce8a1687cec8c8bd883ec73ca41d1"; }; 51 | 52 | }; 53 | 54 | } 55 | #endif -------------------------------------------------------------------------------- /docs/setup/ros_lib/rocon_std_msgs/StringsResponse.h: -------------------------------------------------------------------------------- 1 | #ifndef _ROS_rocon_std_msgs_StringsResponse_h 2 | #define _ROS_rocon_std_msgs_StringsResponse_h 3 | 4 | #include 5 | #include 6 | #include 7 | #include "ros/msg.h" 8 | 9 | namespace rocon_std_msgs 10 | { 11 | 12 | class StringsResponse : public ros::Msg 13 | { 14 | public: 15 | typedef const char* _data_type; 16 | _data_type data; 17 | 18 | StringsResponse(): 19 | data("") 20 | { 21 | } 22 | 23 | virtual int serialize(unsigned char *outbuffer) const 24 | { 25 | int offset = 0; 26 | uint32_t length_data = strlen(this->data); 27 | varToArr(outbuffer + offset, length_data); 28 | offset += 4; 29 | memcpy(outbuffer + offset, this->data, length_data); 30 | offset += length_data; 31 | return offset; 32 | } 33 | 34 | virtual int deserialize(unsigned char *inbuffer) 35 | { 36 | int offset = 0; 37 | uint32_t length_data; 38 | arrToVar(length_data, (inbuffer + offset)); 39 | offset += 4; 40 | for(unsigned int k= offset; k< offset+length_data; ++k){ 41 | inbuffer[k-1]=inbuffer[k]; 42 | } 43 | inbuffer[offset+length_data-1]=0; 44 | this->data = (char *)(inbuffer + offset-1); 45 | offset += length_data; 46 | return offset; 47 | } 48 | 49 | const char * getType(){ return "rocon_std_msgs/StringsResponse"; }; 50 | const char * getMD5(){ return "992ce8a1687cec8c8bd883ec73ca41d1"; }; 51 | 52 | }; 53 | 54 | } 55 | #endif -------------------------------------------------------------------------------- /docs/setup/ros_lib/roscpp/Empty.h: -------------------------------------------------------------------------------- 1 | #ifndef _ROS_SERVICE_Empty_h 2 | #define _ROS_SERVICE_Empty_h 3 | #include 4 | #include 5 | #include 6 | #include "ros/msg.h" 7 | 8 | namespace roscpp 9 | { 10 | 11 | static const char EMPTY[] = "roscpp/Empty"; 12 | 13 | class EmptyRequest : public ros::Msg 14 | { 15 | public: 16 | 17 | EmptyRequest() 18 | { 19 | } 20 | 21 | virtual int serialize(unsigned char *outbuffer) const 22 | { 23 | int offset = 0; 24 | return offset; 25 | } 26 | 27 | virtual int deserialize(unsigned char *inbuffer) 28 | { 29 | int offset = 0; 30 | return offset; 31 | } 32 | 33 | const char * getType(){ return EMPTY; }; 34 | const char * getMD5(){ return "d41d8cd98f00b204e9800998ecf8427e"; }; 35 | 36 | }; 37 | 38 | class EmptyResponse : public ros::Msg 39 | { 40 | public: 41 | 42 | EmptyResponse() 43 | { 44 | } 45 | 46 | virtual int serialize(unsigned char *outbuffer) const 47 | { 48 | int offset = 0; 49 | return offset; 50 | } 51 | 52 | virtual int deserialize(unsigned char *inbuffer) 53 | { 54 | int offset = 0; 55 | return offset; 56 | } 57 | 58 | const char * getType(){ return EMPTY; }; 59 | const char * getMD5(){ return "d41d8cd98f00b204e9800998ecf8427e"; }; 60 | 61 | }; 62 | 63 | class Empty { 64 | public: 65 | typedef EmptyRequest Request; 66 | typedef EmptyResponse Response; 67 | }; 68 | 69 | } 70 | #endif 71 | -------------------------------------------------------------------------------- /docs/setup/ros_lib/shape_msgs/Plane.h: -------------------------------------------------------------------------------- 1 | #ifndef _ROS_shape_msgs_Plane_h 2 | #define _ROS_shape_msgs_Plane_h 3 | 4 | #include 5 | #include 6 | #include 7 | #include "ros/msg.h" 8 | 9 | namespace shape_msgs 10 | { 11 | 12 | class Plane : public ros::Msg 13 | { 14 | public: 15 | float coef[4]; 16 | 17 | Plane(): 18 | coef() 19 | { 20 | } 21 | 22 | virtual int serialize(unsigned char *outbuffer) const 23 | { 24 | int offset = 0; 25 | for( uint32_t i = 0; i < 4; i++){ 26 | offset += serializeAvrFloat64(outbuffer + offset, this->coef[i]); 27 | } 28 | return offset; 29 | } 30 | 31 | virtual int deserialize(unsigned char *inbuffer) 32 | { 33 | int offset = 0; 34 | for( uint32_t i = 0; i < 4; i++){ 35 | offset += deserializeAvrFloat64(inbuffer + offset, &(this->coef[i])); 36 | } 37 | return offset; 38 | } 39 | 40 | const char * getType(){ return "shape_msgs/Plane"; }; 41 | const char * getMD5(){ return "2c1b92ed8f31492f8e73f6a4a44ca796"; }; 42 | 43 | }; 44 | 45 | } 46 | #endif -------------------------------------------------------------------------------- /docs/setup/ros_lib/sound_play/SoundRequestGoal.h: -------------------------------------------------------------------------------- 1 | #ifndef _ROS_sound_play_SoundRequestGoal_h 2 | #define _ROS_sound_play_SoundRequestGoal_h 3 | 4 | #include 5 | #include 6 | #include 7 | #include "ros/msg.h" 8 | #include "sound_play/SoundRequest.h" 9 | 10 | namespace sound_play 11 | { 12 | 13 | class SoundRequestGoal : public ros::Msg 14 | { 15 | public: 16 | typedef sound_play::SoundRequest _sound_request_type; 17 | _sound_request_type sound_request; 18 | 19 | SoundRequestGoal(): 20 | sound_request() 21 | { 22 | } 23 | 24 | virtual int serialize(unsigned char *outbuffer) const 25 | { 26 | int offset = 0; 27 | offset += this->sound_request.serialize(outbuffer + offset); 28 | return offset; 29 | } 30 | 31 | virtual int deserialize(unsigned char *inbuffer) 32 | { 33 | int offset = 0; 34 | offset += this->sound_request.deserialize(inbuffer + offset); 35 | return offset; 36 | } 37 | 38 | const char * getType(){ return "sound_play/SoundRequestGoal"; }; 39 | const char * getMD5(){ return "3bd5e9e7f60b85cc6f1b7662fe6e1903"; }; 40 | 41 | }; 42 | 43 | } 44 | #endif -------------------------------------------------------------------------------- /docs/setup/ros_lib/std_msgs/Bool.h: -------------------------------------------------------------------------------- 1 | #ifndef _ROS_std_msgs_Bool_h 2 | #define _ROS_std_msgs_Bool_h 3 | 4 | #include 5 | #include 6 | #include 7 | #include "ros/msg.h" 8 | 9 | namespace std_msgs 10 | { 11 | 12 | class Bool : public ros::Msg 13 | { 14 | public: 15 | typedef bool _data_type; 16 | _data_type data; 17 | 18 | Bool(): 19 | data(0) 20 | { 21 | } 22 | 23 | virtual int serialize(unsigned char *outbuffer) const 24 | { 25 | int offset = 0; 26 | union { 27 | bool real; 28 | uint8_t base; 29 | } u_data; 30 | u_data.real = this->data; 31 | *(outbuffer + offset + 0) = (u_data.base >> (8 * 0)) & 0xFF; 32 | offset += sizeof(this->data); 33 | return offset; 34 | } 35 | 36 | virtual int deserialize(unsigned char *inbuffer) 37 | { 38 | int offset = 0; 39 | union { 40 | bool real; 41 | uint8_t base; 42 | } u_data; 43 | u_data.base = 0; 44 | u_data.base |= ((uint8_t) (*(inbuffer + offset + 0))) << (8 * 0); 45 | this->data = u_data.real; 46 | offset += sizeof(this->data); 47 | return offset; 48 | } 49 | 50 | const char * getType(){ return "std_msgs/Bool"; }; 51 | const char * getMD5(){ return "8b94c1b53db61fb6aed406028ad6332a"; }; 52 | 53 | }; 54 | 55 | } 56 | #endif -------------------------------------------------------------------------------- /docs/setup/ros_lib/std_msgs/Byte.h: -------------------------------------------------------------------------------- 1 | #ifndef _ROS_std_msgs_Byte_h 2 | #define _ROS_std_msgs_Byte_h 3 | 4 | #include 5 | #include 6 | #include 7 | #include "ros/msg.h" 8 | 9 | namespace std_msgs 10 | { 11 | 12 | class Byte : public ros::Msg 13 | { 14 | public: 15 | typedef int8_t _data_type; 16 | _data_type data; 17 | 18 | Byte(): 19 | data(0) 20 | { 21 | } 22 | 23 | virtual int serialize(unsigned char *outbuffer) const 24 | { 25 | int offset = 0; 26 | union { 27 | int8_t real; 28 | uint8_t base; 29 | } u_data; 30 | u_data.real = this->data; 31 | *(outbuffer + offset + 0) = (u_data.base >> (8 * 0)) & 0xFF; 32 | offset += sizeof(this->data); 33 | return offset; 34 | } 35 | 36 | virtual int deserialize(unsigned char *inbuffer) 37 | { 38 | int offset = 0; 39 | union { 40 | int8_t real; 41 | uint8_t base; 42 | } u_data; 43 | u_data.base = 0; 44 | u_data.base |= ((uint8_t) (*(inbuffer + offset + 0))) << (8 * 0); 45 | this->data = u_data.real; 46 | offset += sizeof(this->data); 47 | return offset; 48 | } 49 | 50 | const char * getType(){ return "std_msgs/Byte"; }; 51 | const char * getMD5(){ return "ad736a2e8818154c487bb80fe42ce43b"; }; 52 | 53 | }; 54 | 55 | } 56 | #endif -------------------------------------------------------------------------------- /docs/setup/ros_lib/std_msgs/Char.h: -------------------------------------------------------------------------------- 1 | #ifndef _ROS_std_msgs_Char_h 2 | #define _ROS_std_msgs_Char_h 3 | 4 | #include 5 | #include 6 | #include 7 | #include "ros/msg.h" 8 | 9 | namespace std_msgs 10 | { 11 | 12 | class Char : public ros::Msg 13 | { 14 | public: 15 | typedef uint8_t _data_type; 16 | _data_type data; 17 | 18 | Char(): 19 | data(0) 20 | { 21 | } 22 | 23 | virtual int serialize(unsigned char *outbuffer) const 24 | { 25 | int offset = 0; 26 | *(outbuffer + offset + 0) = (this->data >> (8 * 0)) & 0xFF; 27 | offset += sizeof(this->data); 28 | return offset; 29 | } 30 | 31 | virtual int deserialize(unsigned char *inbuffer) 32 | { 33 | int offset = 0; 34 | this->data = ((uint8_t) (*(inbuffer + offset))); 35 | offset += sizeof(this->data); 36 | return offset; 37 | } 38 | 39 | const char * getType(){ return "std_msgs/Char"; }; 40 | const char * getMD5(){ return "1bf77f25acecdedba0e224b162199717"; }; 41 | 42 | }; 43 | 44 | } 45 | #endif -------------------------------------------------------------------------------- /docs/setup/ros_lib/std_msgs/Empty.h: -------------------------------------------------------------------------------- 1 | #ifndef _ROS_std_msgs_Empty_h 2 | #define _ROS_std_msgs_Empty_h 3 | 4 | #include 5 | #include 6 | #include 7 | #include "ros/msg.h" 8 | 9 | namespace std_msgs 10 | { 11 | 12 | class Empty : public ros::Msg 13 | { 14 | public: 15 | 16 | Empty() 17 | { 18 | } 19 | 20 | virtual int serialize(unsigned char *outbuffer) const 21 | { 22 | int offset = 0; 23 | return offset; 24 | } 25 | 26 | virtual int deserialize(unsigned char *inbuffer) 27 | { 28 | int offset = 0; 29 | return offset; 30 | } 31 | 32 | const char * getType(){ return "std_msgs/Empty"; }; 33 | const char * getMD5(){ return "d41d8cd98f00b204e9800998ecf8427e"; }; 34 | 35 | }; 36 | 37 | } 38 | #endif -------------------------------------------------------------------------------- /docs/setup/ros_lib/std_msgs/Float64.h: -------------------------------------------------------------------------------- 1 | #ifndef _ROS_std_msgs_Float64_h 2 | #define _ROS_std_msgs_Float64_h 3 | 4 | #include 5 | #include 6 | #include 7 | #include "ros/msg.h" 8 | 9 | namespace std_msgs 10 | { 11 | 12 | class Float64 : public ros::Msg 13 | { 14 | public: 15 | typedef float _data_type; 16 | _data_type data; 17 | 18 | Float64(): 19 | data(0) 20 | { 21 | } 22 | 23 | virtual int serialize(unsigned char *outbuffer) const 24 | { 25 | int offset = 0; 26 | offset += serializeAvrFloat64(outbuffer + offset, this->data); 27 | return offset; 28 | } 29 | 30 | virtual int deserialize(unsigned char *inbuffer) 31 | { 32 | int offset = 0; 33 | offset += deserializeAvrFloat64(inbuffer + offset, &(this->data)); 34 | return offset; 35 | } 36 | 37 | const char * getType(){ return "std_msgs/Float64"; }; 38 | const char * getMD5(){ return "fdb28210bfa9d7c91146260178d9a584"; }; 39 | 40 | }; 41 | 42 | } 43 | #endif -------------------------------------------------------------------------------- /docs/setup/ros_lib/std_msgs/Int16.h: -------------------------------------------------------------------------------- 1 | #ifndef _ROS_std_msgs_Int16_h 2 | #define _ROS_std_msgs_Int16_h 3 | 4 | #include 5 | #include 6 | #include 7 | #include "ros/msg.h" 8 | 9 | namespace std_msgs 10 | { 11 | 12 | class Int16 : public ros::Msg 13 | { 14 | public: 15 | typedef int16_t _data_type; 16 | _data_type data; 17 | 18 | Int16(): 19 | data(0) 20 | { 21 | } 22 | 23 | virtual int serialize(unsigned char *outbuffer) const 24 | { 25 | int offset = 0; 26 | union { 27 | int16_t real; 28 | uint16_t base; 29 | } u_data; 30 | u_data.real = this->data; 31 | *(outbuffer + offset + 0) = (u_data.base >> (8 * 0)) & 0xFF; 32 | *(outbuffer + offset + 1) = (u_data.base >> (8 * 1)) & 0xFF; 33 | offset += sizeof(this->data); 34 | return offset; 35 | } 36 | 37 | virtual int deserialize(unsigned char *inbuffer) 38 | { 39 | int offset = 0; 40 | union { 41 | int16_t real; 42 | uint16_t base; 43 | } u_data; 44 | u_data.base = 0; 45 | u_data.base |= ((uint16_t) (*(inbuffer + offset + 0))) << (8 * 0); 46 | u_data.base |= ((uint16_t) (*(inbuffer + offset + 1))) << (8 * 1); 47 | this->data = u_data.real; 48 | offset += sizeof(this->data); 49 | return offset; 50 | } 51 | 52 | const char * getType(){ return "std_msgs/Int16"; }; 53 | const char * getMD5(){ return "8524586e34fbd7cb1c08c5f5f1ca0e57"; }; 54 | 55 | }; 56 | 57 | } 58 | #endif -------------------------------------------------------------------------------- /docs/setup/ros_lib/std_msgs/Int8.h: -------------------------------------------------------------------------------- 1 | #ifndef _ROS_std_msgs_Int8_h 2 | #define _ROS_std_msgs_Int8_h 3 | 4 | #include 5 | #include 6 | #include 7 | #include "ros/msg.h" 8 | 9 | namespace std_msgs 10 | { 11 | 12 | class Int8 : public ros::Msg 13 | { 14 | public: 15 | typedef int8_t _data_type; 16 | _data_type data; 17 | 18 | Int8(): 19 | data(0) 20 | { 21 | } 22 | 23 | virtual int serialize(unsigned char *outbuffer) const 24 | { 25 | int offset = 0; 26 | union { 27 | int8_t real; 28 | uint8_t base; 29 | } u_data; 30 | u_data.real = this->data; 31 | *(outbuffer + offset + 0) = (u_data.base >> (8 * 0)) & 0xFF; 32 | offset += sizeof(this->data); 33 | return offset; 34 | } 35 | 36 | virtual int deserialize(unsigned char *inbuffer) 37 | { 38 | int offset = 0; 39 | union { 40 | int8_t real; 41 | uint8_t base; 42 | } u_data; 43 | u_data.base = 0; 44 | u_data.base |= ((uint8_t) (*(inbuffer + offset + 0))) << (8 * 0); 45 | this->data = u_data.real; 46 | offset += sizeof(this->data); 47 | return offset; 48 | } 49 | 50 | const char * getType(){ return "std_msgs/Int8"; }; 51 | const char * getMD5(){ return "27ffa0c9c4b8fb8492252bcad9e5c57b"; }; 52 | 53 | }; 54 | 55 | } 56 | #endif -------------------------------------------------------------------------------- /docs/setup/ros_lib/std_msgs/String.h: -------------------------------------------------------------------------------- 1 | #ifndef _ROS_std_msgs_String_h 2 | #define _ROS_std_msgs_String_h 3 | 4 | #include 5 | #include 6 | #include 7 | #include "ros/msg.h" 8 | 9 | namespace std_msgs 10 | { 11 | 12 | class String : public ros::Msg 13 | { 14 | public: 15 | typedef const char* _data_type; 16 | _data_type data; 17 | 18 | String(): 19 | data("") 20 | { 21 | } 22 | 23 | virtual int serialize(unsigned char *outbuffer) const 24 | { 25 | int offset = 0; 26 | uint32_t length_data = strlen(this->data); 27 | varToArr(outbuffer + offset, length_data); 28 | offset += 4; 29 | memcpy(outbuffer + offset, this->data, length_data); 30 | offset += length_data; 31 | return offset; 32 | } 33 | 34 | virtual int deserialize(unsigned char *inbuffer) 35 | { 36 | int offset = 0; 37 | uint32_t length_data; 38 | arrToVar(length_data, (inbuffer + offset)); 39 | offset += 4; 40 | for(unsigned int k= offset; k< offset+length_data; ++k){ 41 | inbuffer[k-1]=inbuffer[k]; 42 | } 43 | inbuffer[offset+length_data-1]=0; 44 | this->data = (char *)(inbuffer + offset-1); 45 | offset += length_data; 46 | return offset; 47 | } 48 | 49 | const char * getType(){ return "std_msgs/String"; }; 50 | const char * getMD5(){ return "992ce8a1687cec8c8bd883ec73ca41d1"; }; 51 | 52 | }; 53 | 54 | } 55 | #endif -------------------------------------------------------------------------------- /docs/setup/ros_lib/std_msgs/UInt16.h: -------------------------------------------------------------------------------- 1 | #ifndef _ROS_std_msgs_UInt16_h 2 | #define _ROS_std_msgs_UInt16_h 3 | 4 | #include 5 | #include 6 | #include 7 | #include "ros/msg.h" 8 | 9 | namespace std_msgs 10 | { 11 | 12 | class UInt16 : public ros::Msg 13 | { 14 | public: 15 | typedef uint16_t _data_type; 16 | _data_type data; 17 | 18 | UInt16(): 19 | data(0) 20 | { 21 | } 22 | 23 | virtual int serialize(unsigned char *outbuffer) const 24 | { 25 | int offset = 0; 26 | *(outbuffer + offset + 0) = (this->data >> (8 * 0)) & 0xFF; 27 | *(outbuffer + offset + 1) = (this->data >> (8 * 1)) & 0xFF; 28 | offset += sizeof(this->data); 29 | return offset; 30 | } 31 | 32 | virtual int deserialize(unsigned char *inbuffer) 33 | { 34 | int offset = 0; 35 | this->data = ((uint16_t) (*(inbuffer + offset))); 36 | this->data |= ((uint16_t) (*(inbuffer + offset + 1))) << (8 * 1); 37 | offset += sizeof(this->data); 38 | return offset; 39 | } 40 | 41 | const char * getType(){ return "std_msgs/UInt16"; }; 42 | const char * getMD5(){ return "1df79edf208b629fe6b81923a544552d"; }; 43 | 44 | }; 45 | 46 | } 47 | #endif -------------------------------------------------------------------------------- /docs/setup/ros_lib/std_msgs/UInt32.h: -------------------------------------------------------------------------------- 1 | #ifndef _ROS_std_msgs_UInt32_h 2 | #define _ROS_std_msgs_UInt32_h 3 | 4 | #include 5 | #include 6 | #include 7 | #include "ros/msg.h" 8 | 9 | namespace std_msgs 10 | { 11 | 12 | class UInt32 : public ros::Msg 13 | { 14 | public: 15 | typedef uint32_t _data_type; 16 | _data_type data; 17 | 18 | UInt32(): 19 | data(0) 20 | { 21 | } 22 | 23 | virtual int serialize(unsigned char *outbuffer) const 24 | { 25 | int offset = 0; 26 | *(outbuffer + offset + 0) = (this->data >> (8 * 0)) & 0xFF; 27 | *(outbuffer + offset + 1) = (this->data >> (8 * 1)) & 0xFF; 28 | *(outbuffer + offset + 2) = (this->data >> (8 * 2)) & 0xFF; 29 | *(outbuffer + offset + 3) = (this->data >> (8 * 3)) & 0xFF; 30 | offset += sizeof(this->data); 31 | return offset; 32 | } 33 | 34 | virtual int deserialize(unsigned char *inbuffer) 35 | { 36 | int offset = 0; 37 | this->data = ((uint32_t) (*(inbuffer + offset))); 38 | this->data |= ((uint32_t) (*(inbuffer + offset + 1))) << (8 * 1); 39 | this->data |= ((uint32_t) (*(inbuffer + offset + 2))) << (8 * 2); 40 | this->data |= ((uint32_t) (*(inbuffer + offset + 3))) << (8 * 3); 41 | offset += sizeof(this->data); 42 | return offset; 43 | } 44 | 45 | const char * getType(){ return "std_msgs/UInt32"; }; 46 | const char * getMD5(){ return "304a39449588c7f8ce2df6e8001c5fce"; }; 47 | 48 | }; 49 | 50 | } 51 | #endif -------------------------------------------------------------------------------- /docs/setup/ros_lib/std_msgs/UInt8.h: -------------------------------------------------------------------------------- 1 | #ifndef _ROS_std_msgs_UInt8_h 2 | #define _ROS_std_msgs_UInt8_h 3 | 4 | #include 5 | #include 6 | #include 7 | #include "ros/msg.h" 8 | 9 | namespace std_msgs 10 | { 11 | 12 | class UInt8 : public ros::Msg 13 | { 14 | public: 15 | typedef uint8_t _data_type; 16 | _data_type data; 17 | 18 | UInt8(): 19 | data(0) 20 | { 21 | } 22 | 23 | virtual int serialize(unsigned char *outbuffer) const 24 | { 25 | int offset = 0; 26 | *(outbuffer + offset + 0) = (this->data >> (8 * 0)) & 0xFF; 27 | offset += sizeof(this->data); 28 | return offset; 29 | } 30 | 31 | virtual int deserialize(unsigned char *inbuffer) 32 | { 33 | int offset = 0; 34 | this->data = ((uint8_t) (*(inbuffer + offset))); 35 | offset += sizeof(this->data); 36 | return offset; 37 | } 38 | 39 | const char * getType(){ return "std_msgs/UInt8"; }; 40 | const char * getMD5(){ return "7c8164229e7d2c17eb95e9231617fdee"; }; 41 | 42 | }; 43 | 44 | } 45 | #endif -------------------------------------------------------------------------------- /docs/setup/ros_lib/std_srvs/Empty.h: -------------------------------------------------------------------------------- 1 | #ifndef _ROS_SERVICE_Empty_h 2 | #define _ROS_SERVICE_Empty_h 3 | #include 4 | #include 5 | #include 6 | #include "ros/msg.h" 7 | 8 | namespace std_srvs 9 | { 10 | 11 | static const char EMPTY[] = "std_srvs/Empty"; 12 | 13 | class EmptyRequest : public ros::Msg 14 | { 15 | public: 16 | 17 | EmptyRequest() 18 | { 19 | } 20 | 21 | virtual int serialize(unsigned char *outbuffer) const 22 | { 23 | int offset = 0; 24 | return offset; 25 | } 26 | 27 | virtual int deserialize(unsigned char *inbuffer) 28 | { 29 | int offset = 0; 30 | return offset; 31 | } 32 | 33 | const char * getType(){ return EMPTY; }; 34 | const char * getMD5(){ return "d41d8cd98f00b204e9800998ecf8427e"; }; 35 | 36 | }; 37 | 38 | class EmptyResponse : public ros::Msg 39 | { 40 | public: 41 | 42 | EmptyResponse() 43 | { 44 | } 45 | 46 | virtual int serialize(unsigned char *outbuffer) const 47 | { 48 | int offset = 0; 49 | return offset; 50 | } 51 | 52 | virtual int deserialize(unsigned char *inbuffer) 53 | { 54 | int offset = 0; 55 | return offset; 56 | } 57 | 58 | const char * getType(){ return EMPTY; }; 59 | const char * getMD5(){ return "d41d8cd98f00b204e9800998ecf8427e"; }; 60 | 61 | }; 62 | 63 | class Empty { 64 | public: 65 | typedef EmptyRequest Request; 66 | typedef EmptyResponse Response; 67 | }; 68 | 69 | } 70 | #endif 71 | -------------------------------------------------------------------------------- /docs/setup/ros_lib/tests/array_test/array_test.pde: -------------------------------------------------------------------------------- 1 | /* 2 | * rosserial::geometry_msgs::PoseArray Test 3 | * Sums an array, publishes sum 4 | */ 5 | 6 | #include 7 | #include 8 | #include 9 | 10 | 11 | ros::NodeHandle nh; 12 | 13 | 14 | bool set_; 15 | 16 | 17 | geometry_msgs::Pose sum_msg; 18 | ros::Publisher p("sum", &sum_msg); 19 | 20 | void messageCb(const geometry_msgs::PoseArray& msg){ 21 | sum_msg.position.x = 0; 22 | sum_msg.position.y = 0; 23 | sum_msg.position.z = 0; 24 | for(int i = 0; i < msg.poses_length; i++) 25 | { 26 | sum_msg.position.x += msg.poses[i].position.x; 27 | sum_msg.position.y += msg.poses[i].position.y; 28 | sum_msg.position.z += msg.poses[i].position.z; 29 | } 30 | digitalWrite(13, HIGH-digitalRead(13)); // blink the led 31 | } 32 | 33 | ros::Subscriber s("poses",messageCb); 34 | 35 | void setup() 36 | { 37 | pinMode(13, OUTPUT); 38 | nh.initNode(); 39 | nh.subscribe(s); 40 | nh.advertise(p); 41 | } 42 | 43 | void loop() 44 | { 45 | p.publish(&sum_msg); 46 | nh.spinOnce(); 47 | delay(10); 48 | } 49 | 50 | -------------------------------------------------------------------------------- /docs/setup/ros_lib/tests/float64_test/float64_test.pde: -------------------------------------------------------------------------------- 1 | /* 2 | * rosserial::std_msgs::Float64 Test 3 | * Receives a Float64 input, subtracts 1.0, and publishes it 4 | */ 5 | 6 | #include 7 | #include 8 | 9 | 10 | ros::NodeHandle nh; 11 | 12 | float x; 13 | 14 | void messageCb( const std_msgs::Float64& msg){ 15 | x = msg.data - 1.0; 16 | digitalWrite(13, HIGH-digitalRead(13)); // blink the led 17 | } 18 | 19 | std_msgs::Float64 test; 20 | ros::Subscriber s("your_topic", &messageCb); 21 | ros::Publisher p("my_topic", &test); 22 | 23 | void setup() 24 | { 25 | pinMode(13, OUTPUT); 26 | nh.initNode(); 27 | nh.advertise(p); 28 | nh.subscribe(s); 29 | } 30 | 31 | void loop() 32 | { 33 | test.data = x; 34 | p.publish( &test ); 35 | nh.spinOnce(); 36 | delay(10); 37 | } 38 | 39 | -------------------------------------------------------------------------------- /docs/setup/ros_lib/tests/time_test/time_test.pde: -------------------------------------------------------------------------------- 1 | /* 2 | * rosserial::std_msgs::Time Test 3 | * Publishes current time 4 | */ 5 | 6 | #include 7 | #include 8 | #include 9 | 10 | 11 | ros::NodeHandle nh; 12 | 13 | std_msgs::Time test; 14 | ros::Publisher p("my_topic", &test); 15 | 16 | void setup() 17 | { 18 | pinMode(13, OUTPUT); 19 | nh.initNode(); 20 | nh.advertise(p); 21 | } 22 | 23 | void loop() 24 | { 25 | test.data = nh.now(); 26 | p.publish( &test ); 27 | nh.spinOnce(); 28 | delay(10); 29 | } 30 | 31 | -------------------------------------------------------------------------------- /docs/setup/ros_lib/tf2_msgs/LookupTransformFeedback.h: -------------------------------------------------------------------------------- 1 | #ifndef _ROS_tf2_msgs_LookupTransformFeedback_h 2 | #define _ROS_tf2_msgs_LookupTransformFeedback_h 3 | 4 | #include 5 | #include 6 | #include 7 | #include "ros/msg.h" 8 | 9 | namespace tf2_msgs 10 | { 11 | 12 | class LookupTransformFeedback : public ros::Msg 13 | { 14 | public: 15 | 16 | LookupTransformFeedback() 17 | { 18 | } 19 | 20 | virtual int serialize(unsigned char *outbuffer) const 21 | { 22 | int offset = 0; 23 | return offset; 24 | } 25 | 26 | virtual int deserialize(unsigned char *inbuffer) 27 | { 28 | int offset = 0; 29 | return offset; 30 | } 31 | 32 | const char * getType(){ return "tf2_msgs/LookupTransformFeedback"; }; 33 | const char * getMD5(){ return "d41d8cd98f00b204e9800998ecf8427e"; }; 34 | 35 | }; 36 | 37 | } 38 | #endif -------------------------------------------------------------------------------- /docs/setup/ros_lib/tf2_msgs/LookupTransformResult.h: -------------------------------------------------------------------------------- 1 | #ifndef _ROS_tf2_msgs_LookupTransformResult_h 2 | #define _ROS_tf2_msgs_LookupTransformResult_h 3 | 4 | #include 5 | #include 6 | #include 7 | #include "ros/msg.h" 8 | #include "geometry_msgs/TransformStamped.h" 9 | #include "tf2_msgs/TF2Error.h" 10 | 11 | namespace tf2_msgs 12 | { 13 | 14 | class LookupTransformResult : public ros::Msg 15 | { 16 | public: 17 | typedef geometry_msgs::TransformStamped _transform_type; 18 | _transform_type transform; 19 | typedef tf2_msgs::TF2Error _error_type; 20 | _error_type error; 21 | 22 | LookupTransformResult(): 23 | transform(), 24 | error() 25 | { 26 | } 27 | 28 | virtual int serialize(unsigned char *outbuffer) const 29 | { 30 | int offset = 0; 31 | offset += this->transform.serialize(outbuffer + offset); 32 | offset += this->error.serialize(outbuffer + offset); 33 | return offset; 34 | } 35 | 36 | virtual int deserialize(unsigned char *inbuffer) 37 | { 38 | int offset = 0; 39 | offset += this->transform.deserialize(inbuffer + offset); 40 | offset += this->error.deserialize(inbuffer + offset); 41 | return offset; 42 | } 43 | 44 | const char * getType(){ return "tf2_msgs/LookupTransformResult"; }; 45 | const char * getMD5(){ return "3fe5db6a19ca9cfb675418c5ad875c36"; }; 46 | 47 | }; 48 | 49 | } 50 | #endif -------------------------------------------------------------------------------- /docs/setup/ros_lib/uuid_msgs/UniqueID.h: -------------------------------------------------------------------------------- 1 | #ifndef _ROS_uuid_msgs_UniqueID_h 2 | #define _ROS_uuid_msgs_UniqueID_h 3 | 4 | #include 5 | #include 6 | #include 7 | #include "ros/msg.h" 8 | 9 | namespace uuid_msgs 10 | { 11 | 12 | class UniqueID : public ros::Msg 13 | { 14 | public: 15 | uint8_t uuid[16]; 16 | 17 | UniqueID(): 18 | uuid() 19 | { 20 | } 21 | 22 | virtual int serialize(unsigned char *outbuffer) const 23 | { 24 | int offset = 0; 25 | for( uint32_t i = 0; i < 16; i++){ 26 | *(outbuffer + offset + 0) = (this->uuid[i] >> (8 * 0)) & 0xFF; 27 | offset += sizeof(this->uuid[i]); 28 | } 29 | return offset; 30 | } 31 | 32 | virtual int deserialize(unsigned char *inbuffer) 33 | { 34 | int offset = 0; 35 | for( uint32_t i = 0; i < 16; i++){ 36 | this->uuid[i] = ((uint8_t) (*(inbuffer + offset))); 37 | offset += sizeof(this->uuid[i]); 38 | } 39 | return offset; 40 | } 41 | 42 | const char * getType(){ return "uuid_msgs/UniqueID"; }; 43 | const char * getMD5(){ return "fec2a93b6f5367ee8112c9c0b41ff310"; }; 44 | 45 | }; 46 | 47 | } 48 | #endif -------------------------------------------------------------------------------- /docs/setup/scripts/1_installRos.sh: -------------------------------------------------------------------------------- 1 | #!/bin/bash 2 | # Install Robot Operating System (ROS) on NVIDIA Jetson 3 | # Setup Locale 4 | sudo update-locale LANG=C LANGUAGE=C LC_ALL=C LC_MESSAGES=POSIX 5 | 6 | # Setup sources.lst 7 | sudo sh -c 'echo "deb http://packages.ros.org/ros/ubuntu $(lsb_release -sc) main" > /etc/apt/sources.list.d/ros-latest.list' 8 | 9 | # Setup keys 10 | sudo apt-key adv --keyserver hkp://ha.pool.sks-keyservers.net:80 --recv-key 421C365BD9FF1F717815A3895523BAEEB01FA116 11 | 12 | # Installation 13 | sudo apt-get update 14 | sudo apt-get -y install ros-kinetic-ros-base 15 | 16 | # Initialize rosdep 17 | sudo apt-get -y install python-rosdep 18 | 19 | # There were some issues with Jeton TX2 Certificates, this is a workaround to run rosdep init 20 | sudo c_rehash /etc/ssl/certs 21 | rosdep init 22 | 23 | # To find available packages, use: 24 | rosdep update 25 | 26 | # Environment Setup 27 | echo "source /opt/ros/kinetic/setup.bash" >> ~/.bashrc 28 | source ~/.bashrc 29 | 30 | # Install rosinstall 31 | sudo apt-get -y install python-rosinstall 32 | -------------------------------------------------------------------------------- /docs/setup/scripts/2_installDependencies.sh: -------------------------------------------------------------------------------- 1 | #!/bin/bash 2 | # Install Jetson Car Dependencies 3 | 4 | # Driver for Teensy 3.2 (Arduino-ish) 5 | sudo apt-get -y install gcc-avr arduino arduino-core 6 | sudo apt-get -y install ros-kinetic-rosserial-arduino ros-kinetic-rosserial ros-kinetic-angles 7 | 8 | # Driver for Logitech Joystick 9 | sudo apt-get -y install ros-kinetic-joy 10 | 11 | # Driver for USB Camera node 12 | sudo apt-get -y install ros-kinetic-cv-bridge ros-kinetic-cv-camera ros-kinetic-jsk-pcl-ros-utils ros-kinetic-roslint 13 | sudo apt-get -y install v4l-utils 14 | 15 | # The current ROS version of librealsense 16 | # NOT WORKING yet 17 | # sudo apt-get -y install ros-kinetic-librealsense 18 | # Remove headers /usr/src since they DO NOT match Jetson TX2. 19 | # cd /usr/src 20 | # sudo rm -rf linux-headers-4.4.0-72* uvcvideo-1.1.1-3-realsense/ 21 | 22 | -------------------------------------------------------------------------------- /docs/tiger_script/0_run_all.sh: -------------------------------------------------------------------------------- 1 | #!/bin/bash 2 | 3 | # Combines scripts below in one file 4 | 5 | sudo ./1_make_custom_kernel.sh 6 | sudo ./3_install_ros.sh 7 | sudo ./4_install_realsense.sh 8 | sudo ./5_install_ros_realsense.sh 9 | 10 | 11 | sudo ./2_build_and_copy_kernel.sh 12 | 13 | # Disable USB autosuspend 14 | sudo sed -i '$s/$/ usbcore.autosuspend=-1/' /boot/extlinux/extlinux.conf 15 | # /bin/ required for echo to work correctly in /bin/sh file 16 | /bin/echo -e "\e[1;32mPlease reboot for changes to take effect.\e[0m" 17 | 18 | -------------------------------------------------------------------------------- /docs/tiger_script/2_build_and_copy_kernel.sh: -------------------------------------------------------------------------------- 1 | #!/bin/bash 2 | 3 | ################################## 4 | ##### BUILD KERNEL MODULES ####### 5 | ################################## 6 | 7 | # Fix makefile compiling issue during make modules 8 | sudo ./scripts/fixMakeFiles.sh 9 | 10 | # @TODO How to automatically select default option during building kernel process? 11 | # During building Joystick kernel module, it would ask us to enter Yes/No option 12 | 13 | cd /usr/src/kernel/kernel-4.4 14 | make prepare 15 | make modules_prepare 16 | make -j6 17 | make modules 18 | make modules_install 19 | 20 | # Copy to current kernel directory 21 | cd /usr/src/kernel/kernel-4.4 22 | sudo cp arch/arm64/boot/zImage /boot/zImage 23 | sudo cp arch/arm64/boot/Image /boot/Image 24 | 25 | -------------------------------------------------------------------------------- /docs/tiger_script/4_install_realsense.sh: -------------------------------------------------------------------------------- 1 | #!/bin/bash 2 | 3 | # Install Realense Library on NVIDA Jetson TX2 4 | 5 | # Prerequisites: 6 | # 1. Finished installed Custom Kernel Modules 7 | # 2. /usr/srsc/kernel/kernel-4.4 is availalbe 8 | 9 | INSTALL_DIR=$PWD 10 | sudo apt-get install libusb-1.0-0-dev pkg-config -y 11 | sudo apt-get install libglfw3-dev -y 12 | sudo apt-get install qtcreator -y 13 | sudo apt-get install cmake -y 14 | 15 | # Install librealsense into home directory 16 | cd $HOME 17 | git clone https://github.com/IntelRealSense/librealsense.git 18 | cd librealsense 19 | # Checkout version 1.11.0 of librealsense, last tested version 20 | git checkout v1.12.1 21 | 22 | # Install Qt libraries 23 | sudo scripts/install_qt.sh 24 | 25 | # Copy over the udev rules so that camera can be run from user space 26 | sudo cp config/99-realsense-libusb.rules /etc/udev/rules.d/ 27 | sudo udevadm control --reload-rules && udevadm trigger 28 | 29 | # Correct libGL path 30 | cd /usr/lib/aarch64-linux-gnu 31 | sudo rm libGL.so 32 | sudo ln -s /usr/lib/aarch64-linux-gnu/tegra/libGL.so libGL.so 33 | 34 | # Make and Install 35 | mkdir build 36 | cd build 37 | cmake .. -DBUILD_EXAMPLES:BOOL=true 38 | sudo make -j6 39 | sudo make install 40 | 41 | 42 | -------------------------------------------------------------------------------- /docs/tiger_script/5_install_ros_realsense.sh: -------------------------------------------------------------------------------- 1 | #!/bin/bash 2 | 3 | # Start patch process 4 | cd /usr/src/kernel/kernel-4.4 5 | # Make sure that there's a config file 6 | file=".config" 7 | if [ -f "$file" ] 8 | then 9 | echo "$file found. Patching UVC Video module" 10 | else 11 | echo "$file not found." 12 | echo "Kernel source must be installed and configured correctly." 13 | echo "Exiting" 14 | exit 1 15 | fi 16 | sudo sed -i 's/.*CONFIG_USB_VIDEO_CLASS=.*/CONFIG_USB_VIDEO_CLASS=m/' .config 17 | sudo patch -p1 -i $HOME/librealsense/scripts/realsense-camera-formats.patch 18 | 19 | # NOTE THAT PATH NEED TO BE CHANGED 20 | rosdep install --from-paths jetson-car/src/vision/realsense_camera/ 21 | 22 | cd /usr/src/ 23 | sudo rm -rf linux-headers-4.4.0-75* 24 | sudo rm -rf uvcvideo-1.1.1-3-realsense/ 25 | -------------------------------------------------------------------------------- /docs/tiger_script/6_setup_workspace.sh: -------------------------------------------------------------------------------- 1 | #!/bin/bash 2 | 3 | sudo echo "source jetson-car/devel/setup.bash" >> ~/.bashrc 4 | 5 | # To communicate to HOST, should be update when using wireless 6 | sudo echo "export ROS_IP=192.168.1.79" >> ~/.bashrc 7 | 8 | # Add HOST IP (your laptop/pc) 9 | sudo echo "192.168.1.78 dat" | sudo tee --append /etc/hosts 10 | 11 | -------------------------------------------------------------------------------- /docs/tiger_script/README.md: -------------------------------------------------------------------------------- 1 | Scripts to install neccesary kernel modules for Car 2 | =================================================== 3 | 4 | 5 | 6 | #### Note 1 : Please run `ssh-keygen -R tegra-ubuntu` before install JetPack to avoid network error. 7 | -------------------------------------------------------------------------------- /docs/tiger_script/enable_gpio_non_root/99-com.rules: -------------------------------------------------------------------------------- 1 | # Install as: /etc/udev/rules.d/99-com.rules 2 | 3 | KERNEL=="gpio*", SUBSYSTEM=="gpio", ACTION=="add", PROGRAM="/usr/local/bin/fix_udev_gpio.sh" 4 | -------------------------------------------------------------------------------- /docs/tiger_script/enable_gpio_non_root/fix_udev_gpio.sh: -------------------------------------------------------------------------------- 1 | #!/bin/bash 2 | # 3 | # This script changes the group ("gpio") and permissions of most files in 4 | # /sys/class/gpio directory, so that gpio could be accessed by non-root 5 | # users in the "gpio" group. 6 | 7 | chown -R root.gpio /sys/class/gpio 8 | chmod 0220 /sys/class/gpio/export 9 | chmod 0220 /sys/class/gpio/unexport 10 | 11 | chown root.gpio /sys/class/gpio/*/direction 12 | chown root.gpio /sys/class/gpio/*/edge 13 | chown root.gpio /sys/class/gpio/*/value 14 | chown root.gpio /sys/class/gpio/*/active_low 15 | chmod 0664 /sys/class/gpio/*/direction 16 | chmod 0664 /sys/class/gpio/*/edge 17 | chmod 0664 /sys/class/gpio/*/value 18 | chmod 0664 /sys/class/gpio/*/active_low 19 | -------------------------------------------------------------------------------- /docs/tiger_script/enable_gpio_non_root/gpio.sh: -------------------------------------------------------------------------------- 1 | #!/bin/bash 2 | # 3 | # This script is used to do simple tests of GPIO. 4 | # Reference: https://developer.ridgerun.com/wiki/index.php/How_to_use_GPIO_signals 5 | 6 | show_usage() 7 | { 8 | printf "\nUsage: gpio.sh [in|out []]\n" 9 | } 10 | 11 | if [ $# -eq 0 -o $# -gt 3 ]; then 12 | show_usage 13 | printf "\nERROR: incorrect number of parameters\n" 14 | exit 255 15 | fi 16 | 17 | if [ ! -d /sys/class/gpio/gpio$1 ]; then 18 | echo $1 > /sys/class/gpio/export 19 | # sleep 1 second here to make sure udev rule takes effect 20 | sleep 1 21 | fi 22 | 23 | if [ $# -eq 1 ]; then 24 | cat /sys/class/gpio/gpio$1/value 25 | exit 0 26 | fi 27 | 28 | if [ "$2" != "in" -a "$2" != "out" ] ; then 29 | show_usage 30 | printf "\nERROR: second parameter must be 'in' or 'out'\n" 31 | exit 255 32 | fi 33 | 34 | echo $2 > /sys/class/gpio/gpio$1/direction 35 | 36 | if [ $# -eq 2 ]; then 37 | cat /sys/class/gpio/gpio$1/value 38 | exit 0 39 | fi 40 | 41 | VAL=$3 42 | if [ $VAL -ne 0 ]; then 43 | VAL=1 44 | fi 45 | 46 | echo $VAL > /sys/class/gpio/gpio$1/value 47 | -------------------------------------------------------------------------------- /docs/tiger_script/enable_gpio_non_root/setup_gpio.sh: -------------------------------------------------------------------------------- 1 | #!/bin/bash 2 | # 3 | # This script is used to enable the user "ubuntu" to access GPIO through 4 | # /sys/class/gpio interface. It only needs to be executed once. Make sure 5 | # you have "fix_udev_gpio.sh" and "99-com.rules" in the same directory 6 | # when you run this script. 7 | 8 | sudo groupadd gpio 9 | sudo usermod -a -G gpio ubuntu 10 | sudo cp fix_udev_gpio.sh /usr/local/bin/ 11 | sudo chmod a+x /usr/local/bin/fix_udev_gpio.sh 12 | 13 | sudo chown -R root.gpio /sys/class/gpio 14 | sudo chmod 0220 /sys/class/gpio/export 15 | sudo chmod 0220 /sys/class/gpio/unexport 16 | 17 | sudo cp 99-com.rules /etc/udev/rules.d/ 18 | -------------------------------------------------------------------------------- /docs/tiger_script/mods/devfreq/Makefile: -------------------------------------------------------------------------------- 1 | obj-$(CONFIG_PM_DEVFREQ) += devfreq.o 2 | obj-$(CONFIG_PM_DEVFREQ_EVENT) += devfreq-event.o 3 | obj-$(CONFIG_DEVFREQ_GOV_SIMPLE_ONDEMAND) += governor_simpleondemand.o 4 | obj-$(CONFIG_DEVFREQ_GOV_PERFORMANCE) += governor_performance.o 5 | obj-$(CONFIG_DEVFREQ_GOV_POWERSAVE) += governor_powersave.o 6 | obj-$(CONFIG_DEVFREQ_GOV_USERSPACE) += governor_userspace.o 7 | obj-$(CONFIG_DEVFREQ_GOV_POD_SCALING) += governor_pod_scaling.o 8 | obj-$(CONFIG_DEVFREQ_GOV_WMARK_SIMPLE) += governor_wmark_simple.o 9 | obj-$(CONFIG_DEVFREQ_GOV_WMARK_ACTIVE) += governor_wmark_active.o 10 | 11 | # DEVFREQ Drivers 12 | obj-$(CONFIG_ARM_EXYNOS4_BUS_DEVFREQ) += exynos/ 13 | obj-$(CONFIG_ARM_EXYNOS5_BUS_DEVFREQ) += exynos/ 14 | obj-$(CONFIG_ARM_TEGRA_DEVFREQ) += tegra-devfreq.o 15 | 16 | # DEVFREQ Event Drivers 17 | obj-$(CONFIG_PM_DEVFREQ_EVENT) += event/ 18 | 19 | ccflags-y += -I./$(src)/ 20 | -------------------------------------------------------------------------------- /docs/tiger_script/mods/devfreq/Makefile (original): -------------------------------------------------------------------------------- 1 | obj-$(CONFIG_PM_DEVFREQ) += devfreq.o 2 | obj-$(CONFIG_PM_DEVFREQ_EVENT) += devfreq-event.o 3 | obj-$(CONFIG_DEVFREQ_GOV_SIMPLE_ONDEMAND) += governor_simpleondemand.o 4 | obj-$(CONFIG_DEVFREQ_GOV_PERFORMANCE) += governor_performance.o 5 | obj-$(CONFIG_DEVFREQ_GOV_POWERSAVE) += governor_powersave.o 6 | obj-$(CONFIG_DEVFREQ_GOV_USERSPACE) += governor_userspace.o 7 | obj-$(CONFIG_DEVFREQ_GOV_POD_SCALING) += governor_pod_scaling.o 8 | obj-$(CONFIG_DEVFREQ_GOV_WMARK_SIMPLE) += governor_wmark_simple.o 9 | obj-$(CONFIG_DEVFREQ_GOV_WMARK_ACTIVE) += governor_wmark_active.o 10 | 11 | # DEVFREQ Drivers 12 | obj-$(CONFIG_ARM_EXYNOS4_BUS_DEVFREQ) += exynos/ 13 | obj-$(CONFIG_ARM_EXYNOS5_BUS_DEVFREQ) += exynos/ 14 | obj-$(CONFIG_ARM_TEGRA_DEVFREQ) += tegra-devfreq.o 15 | 16 | # DEVFREQ Event Drivers 17 | obj-$(CONFIG_PM_DEVFREQ_EVENT) += event/ 18 | -------------------------------------------------------------------------------- /docs/tiger_script/mods/nvadsp/Makefile (original).t18x: -------------------------------------------------------------------------------- 1 | GCOV_PROFILE := y 2 | ccflags-y := -Werror 3 | ccflags-y += -Idrivers/platform/tegra/nvadsp -I$(srctree)/drivers/platform/tegra/nvadsp -I$(srctree)/include 4 | obj-y += os-t18x.o 5 | obj-y += dev-t18x.o 6 | obj-y += acast.o 7 | -------------------------------------------------------------------------------- /docs/tiger_script/mods/nvadsp/Makefile.t18x: -------------------------------------------------------------------------------- 1 | GCOV_PROFILE := y 2 | ccflags-y := -Werror 3 | ccflags-y += -Idrivers/platform/tegra/nvadsp -I$(srctree)/drivers/platform/tegra/nvadsp -I$(srctree)/include -I./$(src)/ 4 | obj-y += os-t18x.o 5 | obj-y += dev-t18x.o 6 | obj-y += acast.o 7 | -------------------------------------------------------------------------------- /docs/tiger_script/mods/rtcpu/Makefile (original).t18x: -------------------------------------------------------------------------------- 1 | ccflags-y := -Werror 2 | ccflags-y += -I$(srctree)/include 3 | ccflags-y += -I$(srctree)/../nvhost 4 | ccflags-y += -I$(srctree) 5 | ccflags-y += -I$(srctree)/../t18x 6 | 7 | obj-y += debug.o 8 | obj-y += tegra-sysfs-mbox.o 9 | obj-y += vi-notify.o 10 | obj-y += hsp-mbox.o 11 | obj-y += tegra-rtcpu-trace.o 12 | obj-y += camchar.o 13 | obj-y += rtcpu-monitor.o 14 | obj-y += tegra-ivc-rpc.o tegra-ivc-rpc-test.o 15 | -------------------------------------------------------------------------------- /docs/tiger_script/mods/rtcpu/Makefile.t18x: -------------------------------------------------------------------------------- 1 | ccflags-y := -Werror 2 | ccflags-y += -I$(srctree)/include 3 | ccflags-y += -I$(srctree)/../nvhost 4 | ccflags-y += -I$(srctree) 5 | ccflags-y += -I$(srctree)/../t18x 6 | ccflags-y += -I./$(src)/ 7 | 8 | obj-y += debug.o 9 | obj-y += tegra-sysfs-mbox.o 10 | obj-y += vi-notify.o 11 | obj-y += hsp-mbox.o 12 | obj-y += tegra-rtcpu-trace.o 13 | obj-y += camchar.o 14 | obj-y += rtcpu-monitor.o 15 | obj-y += tegra-ivc-rpc.o tegra-ivc-rpc-test.o 16 | -------------------------------------------------------------------------------- /docs/tiger_script/mods/sound/change.txt: -------------------------------------------------------------------------------- 1 | /usr/src/kernel/kernel-4.4/sound/soc/tegra-alt/Makefile 2 | -------------------------------------------------------------------------------- /docs/tiger_script/scripts/fixMakeFiles.sh: -------------------------------------------------------------------------------- 1 | #!/bin/bash 2 | cp ./mods/nvadsp/Makefile.t18x /usr/src/kernel/t18x/drivers/platform/tegra/nvadsp 3 | cp ./mods/rtcpu/Makefile.t18x /usr/src/kernel/t18x/drivers/platform/tegra/rtcpu 4 | cp ./mods/devfreq/Makefile /usr/src/kernel/kernel-4.4/drivers/devfreq 5 | cp ./mods/nvgpu/Makefile.nvgpu /usr/src/kernel/nvgpu/drivers/gpu/nvgpu 6 | cp ./mods/sound/Makefile /usr/src/kernel/kernel-4.4/sound/soc/tegra-alt 7 | # Haven't been able to figure out how to correct this properly: 8 | cp /usr/src/kernel/kernel-4.4/drivers/media/platform/tegra/vi/vi.h /usr/src/kernel/t18x/drivers/video/tegra/host/vi 9 | 10 | 11 | -------------------------------------------------------------------------------- /model/basic_steering_model.h5: -------------------------------------------------------------------------------- https://raw.githubusercontent.com/datlife/jetson-car/a1bae7b8ad2af8ef9fd33cdd76421ebe3ff5ca7f/model/basic_steering_model.h5 -------------------------------------------------------------------------------- /src/controller/.activate.py.swp: -------------------------------------------------------------------------------- https://raw.githubusercontent.com/datlife/jetson-car/a1bae7b8ad2af8ef9fd33cdd76421ebe3ff5ca7f/src/controller/.activate.py.swp -------------------------------------------------------------------------------- /src/controller/CMakeLists.txt: -------------------------------------------------------------------------------- 1 | cmake_minimum_required(VERSION 2.8.3) 2 | project(controller) 3 | 4 | find_package(catkin REQUIRED COMPONENTS 5 | rc_car_msgs 6 | joy 7 | roscpp 8 | ) 9 | ################################################ 10 | ## Declare ROS dynamic reconfigure parameters ## 11 | ################################################ 12 | catkin_package(CATKIN_DEPENDS rc_car_msgs joy roscpp) 13 | ########### 14 | ## Build ## 15 | ########### 16 | include_directories(${catkin_INCLUDE_DIRS}) 17 | ## Declare a C++ executable 18 | add_executable(controller_node src/joystick_node.cpp) 19 | add_dependencies(controller_node ${catkin_EXPORTED_TARGETS}) 20 | target_link_libraries(controller_node ${catkin_LIBRARIES}) 21 | 22 | ############# 23 | ## Install ## 24 | ############# 25 | 26 | ############# 27 | ## Testing ## 28 | ############# 29 | 30 | -------------------------------------------------------------------------------- /src/controller/FLAGS.py: -------------------------------------------------------------------------------- 1 | # Image Size 2 | HEIGHT = 46 3 | WIDTH = 160 4 | CHANNELS = 3 5 | # output dimension from RNN 6 | OUTPUT_DIM = 3 7 | 8 | # RNN SIZE 9 | HIDDEN_UNITS = 32 10 | STEER_CORRECTION = 0.2 11 | 12 | # HYPER-PARAMETER 13 | LEARN_RATE = 0.0001 14 | KEEP_PROP = 0.3 15 | EPOCHS = 5 16 | BATCH_SIZE = 2 # Be careful, stateful RNN requires to state batch size ahead 17 | TIME_STEPS = 10 # For RNN 18 | INIT = 'he_uniform' 19 | 20 | # INPUT 21 | DRIVING_LOG = './data/driving_log.csv' 22 | IMG_DIR = './data/IMG' 23 | 24 | # CROP FACTOR - remove top and bottom of images 25 | TOP = 70 26 | BOTTOM = 20 27 | -------------------------------------------------------------------------------- /src/controller/cfg/paths.yaml: -------------------------------------------------------------------------------- 1 | # PATHS ARE USED in each nodes, will be used via launch file under `rosparam load iyaml_file` 2 | model_path: "/home/nvidia/jetson-car/models/basic_steering_model.json" 3 | 4 | -------------------------------------------------------------------------------- /src/controller/include/autopilot.h: -------------------------------------------------------------------------------- 1 | // 2 | // Created by nvidia on 4/4/17. 3 | // 4 | 5 | #ifndef CAR_AUTOPILOT_H 6 | #define CAR_AUTOPILOT_H 7 | 8 | class Pilot{ 9 | public: 10 | // Default Constructor 11 | Pilot(); 12 | private: 13 | enum {OFF, ON}; 14 | ros::NodeHandle node_handle_; 15 | ros::Publisher car_pub_; 16 | ros::Subscriber joy_sub_; 17 | ros::Subscriber vision_sub; 18 | 19 | void joyCallback(const sensor_msgs::Joy::ConstPtr& joy); 20 | void visionCallback(const sensor_msgs::Image::ConstPtr& image); 21 | }; 22 | #endif //CAR_AUTOPILOT_H 23 | -------------------------------------------------------------------------------- /src/controller/launch/autopilot.launch: -------------------------------------------------------------------------------- 1 | 2 | 3 | 4 | -------------------------------------------------------------------------------- /src/controller/launch/manual.launch: -------------------------------------------------------------------------------- 1 | 2 | 3 | 4 | 5 | 6 | 7 | 8 | 9 | 10 | 11 | 12 | 13 | 14 | 15 | 16 | 17 | 18 | 19 | 20 | 21 | 22 | 23 | 24 | 25 | 26 | 27 | 28 | 29 | 30 | 31 | 32 | 33 | 34 | -------------------------------------------------------------------------------- /src/controller/launch/manual.launch.old: -------------------------------------------------------------------------------- 1 | 2 | 3 | 4 | 5 | 6 | 7 | 8 | 9 | 10 | 11 | 12 | 13 | 14 | 15 | 16 | 17 | 18 | 19 | 20 | 21 | 22 | 23 | 24 | 25 | 26 | 27 | 28 | 29 | 30 | 31 | 32 | 33 | 34 | -------------------------------------------------------------------------------- /src/controller/package.xml: -------------------------------------------------------------------------------- 1 | 2 | 3 | controller 4 | 0.0.0 5 | Activate autonomous/manual mode 6 | Dat Nguyen 7 | MIT 8 | 9 | catkin 10 | rc_car_msgs 11 | joy 12 | roscpp 13 | 14 | rc_car_msgs 15 | joy 16 | roscpp 17 | 18 | 19 | 20 | 21 | 22 | 23 | -------------------------------------------------------------------------------- /src/controller/src/autopilot.cpp: -------------------------------------------------------------------------------- 1 | // 2 | // Created by nvidia on 4/4/17. 3 | // 4 | #include 5 | #include 6 | #include 7 | #include 8 | #include 9 | #include 10 | #include 11 | #include 12 | 13 | Pilot::Pilot(){ 14 | 15 | } 16 | 17 | void Pilot::joyCallback(const sensor_msgs::Joy::ConstPtr& joy){ 18 | 19 | } 20 | 21 | void Pilot::visionCallback(const sensor_msgs::Image::ConstPtr& image){ 22 | 23 | } 24 | -------------------------------------------------------------------------------- /src/navigation/razor_imu_9dof/CMakeLists.txt: -------------------------------------------------------------------------------- 1 | cmake_minimum_required(VERSION 2.8.3) 2 | project(razor_imu_9dof) 3 | 4 | find_package(catkin REQUIRED COMPONENTS dynamic_reconfigure) 5 | 6 | generate_dynamic_reconfigure_options(cfg/imu.cfg) 7 | 8 | catkin_package(DEPENDS CATKIN DEPENDS dynamic_reconfigure) 9 | 10 | install(DIRECTORY launch 11 | DESTINATION ${CATKIN_PACKAGE_SHARE_DESTINATION} 12 | ) 13 | 14 | install(DIRECTORY config 15 | DESTINATION ${CATKIN_PACKAGE_SHARE_DESTINATION} 16 | ) 17 | 18 | install(DIRECTORY cfg 19 | DESTINATION ${CATKIN_PACKAGE_SHARE_DESTINATION} 20 | ) 21 | 22 | install(DIRECTORY src 23 | DESTINATION ${CATKIN_PACKAGE_SHARE_DESTINATION} 24 | ) 25 | 26 | install(DIRECTORY magnetometer_calibration 27 | DESTINATION ${CATKIN_PACKAGE_SHARE_DESTINATION} 28 | ) 29 | 30 | catkin_install_python(PROGRAMS 31 | nodes/imu_node.py 32 | DESTINATION ${CATKIN_PACKAGE_SHARE_DESTINATION}/nodes 33 | ) 34 | -------------------------------------------------------------------------------- /src/navigation/razor_imu_9dof/cfg/imu.cfg: -------------------------------------------------------------------------------- 1 | #!/usr/bin/env python 2 | PACKAGE = "razor_imu_m0" 3 | 4 | from dynamic_reconfigure.parameter_generator_catkin import * 5 | 6 | gen = ParameterGenerator() 7 | gen.add("yaw_calibration", double_t, 0, "Yaw Calibration", 0, -10, 10) 8 | 9 | exit(gen.generate(PACKAGE, "razor_imu_9dof", "imu")) 10 | -------------------------------------------------------------------------------- /src/navigation/razor_imu_9dof/config/my_razor.yaml: -------------------------------------------------------------------------------- 1 | ## USB port 2 | port: /dev/ttyACM0 3 | 4 | 5 | ##### Calibration #### 6 | ### accelerometer 7 | accel_x_min: -250.0 8 | accel_x_max: 250.0 9 | accel_y_min: -250.0 10 | accel_y_max: 250.0 11 | accel_z_min: -250.0 12 | accel_z_max: 250.0 13 | 14 | ### magnetometer 15 | # standard calibration 16 | magn_x_min: -600.0 17 | magn_x_max: 600.0 18 | magn_y_min: -600.0 19 | magn_y_max: 600.0 20 | magn_z_min: -600.0 21 | magn_z_max: 600.0 22 | 23 | # extended calibration 24 | calibration_magn_use_extended: false 25 | magn_ellipsoid_center: [0, 0, 0] 26 | magn_ellipsoid_transform: [[0, 0, 0], [0, 0, 0], [0, 0, 0]] 27 | 28 | # AHRS to robot calibration 29 | imu_yaw_calibration: 0.0 30 | 31 | ### gyroscope 32 | gyro_average_offset_x: 0.0 33 | gyro_average_offset_y: 0.0 34 | gyro_average_offset_z: 0.0 35 | -------------------------------------------------------------------------------- /src/navigation/razor_imu_9dof/config/razor.yaml: -------------------------------------------------------------------------------- 1 | # USB port 2 | port: /dev/ttyUSB0 3 | 4 | 5 | ##### Calibration #### 6 | ### accelerometer 7 | accel_x_min: -250.0 8 | accel_x_max: 250.0 9 | accel_y_min: -250.0 10 | accel_y_max: 250.0 11 | accel_z_min: -250.0 12 | accel_z_max: 250.0 13 | 14 | ### magnetometer 15 | # standard calibration 16 | magn_x_min: -600.0 17 | magn_x_max: 600.0 18 | magn_y_min: -600.0 19 | magn_y_max: 600.0 20 | magn_z_min: -600.0 21 | magn_z_max: 600.0 22 | 23 | # extended calibration 24 | calibration_magn_use_extended: false 25 | magn_ellipsoid_center: [0, 0, 0] 26 | magn_ellipsoid_transform: [[0, 0, 0], [0, 0, 0], [0, 0, 0]] 27 | 28 | # AHRS to robot calibration 29 | imu_yaw_calibration: 0.0 30 | 31 | ### gyroscope 32 | gyro_average_offset_x: 0.0 33 | gyro_average_offset_y: 0.0 34 | gyro_average_offset_z: 0.0 35 | -------------------------------------------------------------------------------- /src/navigation/razor_imu_9dof/launch/start.lauch: -------------------------------------------------------------------------------- 1 | 2 | 3 | 4 | 5 | 6 | 7 | -------------------------------------------------------------------------------- /src/navigation/razor_imu_9dof/launch/start.launch: -------------------------------------------------------------------------------- 1 | 2 | 3 | 4 | 5 | 6 | 7 | -------------------------------------------------------------------------------- /src/navigation/razor_imu_9dof/magnetometer_calibration/Matlab/magnetometer_calibration/ellipsoid_fit_license.txt: -------------------------------------------------------------------------------- 1 | Copyright (c) 2009, Yury Petrov 2 | All rights reserved. 3 | 4 | Redistribution and use in source and binary forms, with or without 5 | modification, are permitted provided that the following conditions are 6 | met: 7 | 8 | * Redistributions of source code must retain the above copyright 9 | notice, this list of conditions and the following disclaimer. 10 | * Redistributions in binary form must reproduce the above copyright 11 | notice, this list of conditions and the following disclaimer in 12 | the documentation and/or other materials provided with the distribution 13 | 14 | THIS SOFTWARE IS PROVIDED BY THE COPYRIGHT HOLDERS AND CONTRIBUTORS "AS IS" 15 | AND ANY EXPRESS OR IMPLIED WARRANTIES, INCLUDING, BUT NOT LIMITED TO, THE 16 | IMPLIED WARRANTIES OF MERCHANTABILITY AND FITNESS FOR A PARTICULAR PURPOSE 17 | ARE DISCLAIMED. IN NO EVENT SHALL THE COPYRIGHT OWNER OR CONTRIBUTORS BE 18 | LIABLE FOR ANY DIRECT, INDIRECT, INCIDENTAL, SPECIAL, EXEMPLARY, OR 19 | CONSEQUENTIAL DAMAGES (INCLUDING, BUT NOT LIMITED TO, PROCUREMENT OF 20 | SUBSTITUTE GOODS OR SERVICES; LOSS OF USE, DATA, OR PROFITS; OR BUSINESS 21 | INTERRUPTION) HOWEVER CAUSED AND ON ANY THEORY OF LIABILITY, WHETHER IN 22 | CONTRACT, STRICT LIABILITY, OR TORT (INCLUDING NEGLIGENCE OR OTHERWISE) 23 | ARISING IN ANY WAY OUT OF THE USE OF THIS SOFTWARE, EVEN IF ADVISED OF THE 24 | POSSIBILITY OF SUCH DAMAGE. 25 | -------------------------------------------------------------------------------- /src/navigation/razor_imu_9dof/magnetometer_calibration/Processing/Magnetometer_calibration/data/Univers-66.vlw: -------------------------------------------------------------------------------- https://raw.githubusercontent.com/datlife/jetson-car/a1bae7b8ad2af8ef9fd33cdd76421ebe3ff5ca7f/src/navigation/razor_imu_9dof/magnetometer_calibration/Processing/Magnetometer_calibration/data/Univers-66.vlw -------------------------------------------------------------------------------- /src/navigation/razor_imu_9dof/package.xml: -------------------------------------------------------------------------------- 1 | 2 | razor_imu_9dof 3 | 1.1.1 4 | 5 | The navigation package is used to determine the current pose of the car (Velocity, Odom) 6 | razor_imu_9dof is a package that provides a ROS driver 7 | for the Sparkfun Razor IMU 9DOF. It also provides Arduino 8 | firmware that runs on the Razor board, and which must be 9 | installed on the Razor board for the system to work. A node 10 | which displays the attitude (roll, pitch and yaw) of the Razor board 11 | (or any IMU) is provided for testing. 12 | 13 | Kristof Robot 14 | 15 | BSD 16 | 17 | Tang Tiong Yew 18 | Kristof Robot 19 | Paul Bouchier 20 | Peter Bartz 21 | 22 | http://ros.org/wiki/razor_imu_9dof 23 | 24 | catkin 25 | dynamic_reconfigure 26 | 27 | rospy 28 | tf 29 | sensor_msgs 30 | python-serial 31 | dynamic_reconfigure 32 | 33 | 34 | 35 | -------------------------------------------------------------------------------- /src/rc_car_msgs/CMakeLists.txt: -------------------------------------------------------------------------------- 1 | cmake_minimum_required(VERSION 2.8.3) 2 | project(rc_car_msgs) 3 | 4 | find_package(catkin REQUIRED COMPONENTS 5 | message_generation 6 | std_msgs 7 | sensor_msgs 8 | ) 9 | 10 | add_message_files( 11 | FILES 12 | CarController.msg 13 | CarInfo.msg 14 | CarRecorder.msg 15 | ) 16 | 17 | generate_messages( 18 | DEPENDENCIES 19 | std_msgs 20 | sensor_msgs 21 | rc_car_msgs 22 | ) 23 | 24 | catkin_package( 25 | # INCLUDE_DIRS include 26 | # LIBRARIES rc_car_msgs 27 | CATKIN_DEPENDS message_runtime std_msgs sensor_msgs 28 | # DEPENDS system_lib 29 | ) 30 | 31 | ########### 32 | ## Build ## 33 | ########### 34 | 35 | include_directories( 36 | ${catkin_INCLUDE_DIRS} 37 | ) 38 | 39 | 40 | ############# 41 | ## Install ## 42 | ############# 43 | 44 | # all install targets should use catkin DESTINATION variables 45 | 46 | ## Mark other files for installation (e.g. launch and bag files, etc.) 47 | # install(FILES 48 | # # myfile1 49 | # # myfile2 50 | # DESTINATION ${CATKIN_PACKAGE_SHARE_DESTINATION} 51 | # ) 52 | 53 | ############# 54 | ## Testing ## 55 | ############# 56 | 57 | ## Add gtest based cpp test target and link libraries 58 | # catkin_add_gtest(${PROJECT_NAME}-test test/test_rc_car_msgs.cpp) 59 | # if(TARGET ${PROJECT_NAME}-test) 60 | # target_link_libraries(${PROJECT_NAME}-test ${PROJECT_NAME}) 61 | # endif() 62 | 63 | ## Add folders to be run by python nosetests 64 | # catkin_add_nosetests(test) 65 | -------------------------------------------------------------------------------- /src/rc_car_msgs/msg/CarController.msg: -------------------------------------------------------------------------------- 1 | float32 throttle 2 | float32 steer 3 | -------------------------------------------------------------------------------- /src/rc_car_msgs/msg/CarInfo.msg: -------------------------------------------------------------------------------- 1 | float32 throttle 2 | float32 steer 3 | uint8 rpm 4 | uint8 speed 5 | -------------------------------------------------------------------------------- /src/rc_car_msgs/msg/CarRecorder.msg: -------------------------------------------------------------------------------- 1 | string img_path 2 | float32 steer 3 | float32 throttle 4 | float32 speed 5 | -------------------------------------------------------------------------------- /src/rc_car_msgs/package.xml: -------------------------------------------------------------------------------- 1 | 2 | 3 | rc_car_msgs 4 | 0.0.0 5 | ROS Messsage definitions for RC Cars. Provide SPEED, STEER ANGLE, THROOTLE 6 | 7 | Dat Nguyen 8 | MIT 9 | https://github.com/dat-ai/jetson-car 10 | Dat Nguyen 11 | 12 | catkin 13 | message_generation 14 | std_msgs 15 | sensor_msgs 16 | 17 | std_msgs 18 | sensor_msgs 19 | message_runtime 20 | 21 | 22 | -------------------------------------------------------------------------------- /src/record_data/CMakeLists.txt: -------------------------------------------------------------------------------- 1 | cmake_minimum_required(VERSION 2.8.3) 2 | project(record_data) 3 | 4 | find_package(catkin REQUIRED COMPONENTS 5 | rospy 6 | rc_car_msgs 7 | std_msgs 8 | ) 9 | 10 | 11 | catkin_package( 12 | # INCLUDE_DIRS include 13 | # LIBRARIES record_data 14 | CATKIN_DEPENDS rospy rc_car_msgs std_msgs 15 | # DEPENDS system_lib 16 | ) 17 | 18 | ########### 19 | ## Build ## 20 | ########### 21 | 22 | include_directories( 23 | ${catkin_INCLUDE_DIRS} 24 | ) 25 | ############# 26 | ## Install ## 27 | ############# 28 | 29 | catkin_install_python(PROGRAMS 30 | recorder.py 31 | DESTINATION ${CATKIN_PACKAGE_SHARE_DESTINATION} 32 | ) 33 | 34 | 35 | 36 | ## Testing ## 37 | ############# 38 | 39 | ## Add gtest based cpp test target and link libraries 40 | # catkin_add_gtest(${PROJECT_NAME}-test test/test_record_data.cpp) 41 | # if(TARGET ${PROJECT_NAME}-test) 42 | # target_link_libraries(${PROJECT_NAME}-test ${PROJECT_NAME}) 43 | # endif() 44 | 45 | ## Add folders to be run by python nosetests 46 | # catkin_add_nosetests(test) 47 | -------------------------------------------------------------------------------- /src/record_data/launch/recorder.launch: -------------------------------------------------------------------------------- 1 | 2 | 3 | 4 | -------------------------------------------------------------------------------- /src/record_data/launch/recorder.launch.old: -------------------------------------------------------------------------------- 1 | 2 | 3 | 4 | 5 | -------------------------------------------------------------------------------- /src/record_data/package.xml: -------------------------------------------------------------------------------- 1 | 2 | 3 | record_data 4 | 0.0.0 5 | The record_data package 6 | 7 | ubuntu 8 | 9 | 10 | TODO 11 | 12 | 13 | catkin 14 | rospy 15 | rc_car_msgs 16 | std_msgs 17 | 18 | joy 19 | std_msgs 20 | rc_car_msgs 21 | rospy 22 | 23 | 24 | 25 | 26 | 27 | 28 | 29 | -------------------------------------------------------------------------------- /src/vision/realsense_camera/launch/get_debug_info.launch: -------------------------------------------------------------------------------- 1 | 2 | 3 | 4 | 5 | -------------------------------------------------------------------------------- /src/vision/realsense_camera/librealsense: -------------------------------------------------------------------------------- 1 | /home/nvidia/librealsense/ -------------------------------------------------------------------------------- /src/vision/realsense_camera/licenses/License.txt: -------------------------------------------------------------------------------- 1 | Copyright (c) 2016, Intel Corporation 2 | All rights reserved. 3 | 4 | Redistribution and use in source and binary forms, with or without modification, are permitted provided that the following conditions are met: 5 | 6 | 1. Redistributions of source code must retain the above copyright notice, this list of conditions and the following disclaimer. 7 | 8 | 2. Redistributions in binary form must reproduce the above copyright notice, this list of conditions and the following disclaimer in the documentation and/or other materials provided with the distribution. 9 | 10 | 3. Neither the name of the copyright holder nor the names of its contributors may be used to endorse or promote products derived from this software without specific prior written permission. 11 | 12 | THIS SOFTWARE IS PROVIDED BY THE COPYRIGHT HOLDERS AND CONTRIBUTORS "AS IS" AND ANY EXPRESS OR IMPLIED WARRANTIES, INCLUDING, BUT NOT LIMITED TO, THE IMPLIED WARRANTIES OF MERCHANTABILITY AND FITNESS FOR A PARTICULAR PURPOSE ARE DISCLAIMED. IN NO EVENT SHALL THE COPYRIGHT HOLDER OR CONTRIBUTORS BE LIABLE FOR ANY DIRECT, INDIRECT, INCIDENTAL, SPECIAL, EXEMPLARY, OR CONSEQUENTIAL DAMAGES (INCLUDING, BUT NOT LIMITED TO, PROCUREMENT OF SUBSTITUTE GOODS OR SERVICES; LOSS OF USE, DATA, OR PROFITS; OR BUSINESS INTERRUPTION) HOWEVER CAUSED AND ON ANY THEORY OF LIABILITY, WHETHER IN CONTRACT, STRICT LIABILITY, OR TORT (INCLUDING NEGLIGENCE OR OTHERWISE) ARISING IN ANY WAY OUT OF THE USE OF THIS SOFTWARE, EVEN IF ADVISED OF THE POSSIBILITY OF SUCH DAMAGE. 13 | -------------------------------------------------------------------------------- /src/vision/realsense_camera/msg/IMUInfo.msg: -------------------------------------------------------------------------------- 1 | # header.frame_id is either set to "imu_accel" or "imu_gyro" 2 | # to distinguish between "accel" and "gyro" info. 3 | std_msgs/Header header 4 | float64[12] data 5 | float64[3] noise_variances 6 | float64[3] bias_variances -------------------------------------------------------------------------------- /src/vision/realsense_camera/nodelet_plugins.xml: -------------------------------------------------------------------------------- 1 | 2 | 3 | 4 | Intel(R) RealSense(TM) R200 Camera nodelet. 5 | 6 | 7 | 8 | 9 | 10 | Intel(R) RealSense(TM) F200 Camera nodelet. 11 | 12 | 13 | 14 | 15 | 16 | Intel(R) RealSense(TM) SR300 Camera nodelet. 17 | 18 | 19 | 20 | 21 | 22 | Intel(R) RealSense(TM) ZR300 Camera nodelet. 23 | 24 | 25 | 26 | -------------------------------------------------------------------------------- /src/vision/realsense_camera/srv/CameraConfiguration.srv: -------------------------------------------------------------------------------- 1 | --- 2 | string configuration_str 3 | -------------------------------------------------------------------------------- /src/vision/realsense_camera/srv/ForcePower.srv: -------------------------------------------------------------------------------- 1 | bool power_on # true - to power on camera, false - to power off camera 2 | --- 3 | -------------------------------------------------------------------------------- /src/vision/realsense_camera/srv/GetIMUInfo.srv: -------------------------------------------------------------------------------- 1 | --- 2 | IMUInfo accel 3 | IMUInfo gyro 4 | -------------------------------------------------------------------------------- /src/vision/realsense_camera/srv/IsPowered.srv: -------------------------------------------------------------------------------- 1 | --- 2 | bool is_powered 3 | -------------------------------------------------------------------------------- /src/vision/realsense_camera/srv/SetPower.srv: -------------------------------------------------------------------------------- 1 | bool power_on # true - to power on camera, false - to power off camera 2 | --- 3 | bool success # false - only if camera has subscribers, and attempted power off 4 | -------------------------------------------------------------------------------- /src/vision/realsense_camera/test/f200_nodelet_disable_color.test: -------------------------------------------------------------------------------- 1 | 2 | 3 | 4 | 5 | 6 | 7 | 8 | 9 | 10 | 11 | 12 | 13 | 14 | 17 | 18 | -------------------------------------------------------------------------------- /src/vision/realsense_camera/test/f200_nodelet_disable_depth.test: -------------------------------------------------------------------------------- 1 | 2 | 3 | 4 | 5 | 6 | 7 | 8 | 9 | 10 | 11 | 12 | 13 | 14 | 17 | 18 | -------------------------------------------------------------------------------- /src/vision/realsense_camera/test/f200_nodelet_enable_ir.test: -------------------------------------------------------------------------------- 1 | 2 | 3 | 4 | 5 | 6 | 7 | 8 | 9 | 10 | 11 | 12 | -------------------------------------------------------------------------------- /src/vision/realsense_camera/test/f200_nodelet_modify_params.test: -------------------------------------------------------------------------------- 1 | 2 | 3 | 4 | 5 | 6 | 7 | 8 | 9 | 10 | 11 | 12 | 13 | 14 | 15 | 16 | -------------------------------------------------------------------------------- /src/vision/realsense_camera/test/f200_nodelet_resolution.test: -------------------------------------------------------------------------------- 1 | 2 | 3 | 4 | 5 | 6 | 7 | -------------------------------------------------------------------------------- /src/vision/realsense_camera/test/f200_nodelet_rgbd.test: -------------------------------------------------------------------------------- 1 | 2 | 3 | 4 | 5 | 6 | 7 | 8 | 9 | 10 | 11 | -------------------------------------------------------------------------------- /src/vision/realsense_camera/test/files/bat-tests/check_librealsense_installed.test: -------------------------------------------------------------------------------- 1 | 2 | 3 | 5 | 6 | -------------------------------------------------------------------------------- /src/vision/realsense_camera/test/files/bat-tests/check_realsense_camera_nodelet_built.test: -------------------------------------------------------------------------------- 1 | 2 | 3 | 5 | 6 | -------------------------------------------------------------------------------- /src/vision/realsense_camera/test/files/bat-tests/f200_nodelet_camera_service_power_force_off_and_on_with_subscriber.test: -------------------------------------------------------------------------------- 1 | 2 | 3 | 4 | 5 | 6 | 7 | 8 | 9 | 10 | 11 | 12 | 13 | 17 | 18 | -------------------------------------------------------------------------------- /src/vision/realsense_camera/test/files/bat-tests/f200_nodelet_camera_service_power_set_off_and_on_with_no_subscriber.test: -------------------------------------------------------------------------------- 1 | 2 | 3 | 4 | 5 | 6 | 7 | 8 | 9 | 10 | 11 | 12 | 13 | 14 | 15 | 21 | 22 | -------------------------------------------------------------------------------- /src/vision/realsense_camera/test/files/bat-tests/f200_nodelet_transforms_enable_publish_tf.test: -------------------------------------------------------------------------------- 1 | 2 | 3 | 4 | 5 | 6 | 7 | 8 | 9 | 10 | 11 | 12 | 13 | 14 | 15 | 16 | 17 | 18 | 19 | 24 | 25 | -------------------------------------------------------------------------------- /src/vision/realsense_camera/test/files/bat-tests/r200_nodelet_camera_service_power_force_off_and_on_with_subscriber.test: -------------------------------------------------------------------------------- 1 | 2 | 3 | 4 | 5 | 6 | 7 | 8 | 9 | 10 | 11 | 12 | 13 | 17 | 18 | -------------------------------------------------------------------------------- /src/vision/realsense_camera/test/files/bat-tests/r200_nodelet_camera_service_power_set_off_and_on_with_no_subscriber.test: -------------------------------------------------------------------------------- 1 | 2 | 3 | 4 | 5 | 6 | 7 | 8 | 9 | 10 | 11 | 12 | 13 | 14 | 15 | 21 | 22 | -------------------------------------------------------------------------------- /src/vision/realsense_camera/test/files/bat-tests/r200_nodelet_transforms_enable_publish_tf.test: -------------------------------------------------------------------------------- 1 | 2 | 3 | 4 | 5 | 6 | 7 | 8 | 9 | 10 | 11 | 12 | 13 | 14 | 15 | 20 | 21 | -------------------------------------------------------------------------------- /src/vision/realsense_camera/test/files/bat-tests/sr300_nodelet_camera_service_power_force_off_and_on_with_subscriber.test: -------------------------------------------------------------------------------- 1 | 2 | 3 | 4 | 5 | 6 | 7 | 8 | 9 | 10 | 11 | 12 | 13 | 17 | 18 | -------------------------------------------------------------------------------- /src/vision/realsense_camera/test/files/bat-tests/sr300_nodelet_camera_service_power_set_off_and_on_with_no_subscriber.test: -------------------------------------------------------------------------------- 1 | 2 | 3 | 4 | 5 | 6 | 7 | 8 | 9 | 10 | 11 | 12 | 13 | 14 | 15 | 21 | 22 | -------------------------------------------------------------------------------- /src/vision/realsense_camera/test/files/bat-tests/sr300_nodelet_transforms_enable_publish_tf.test: -------------------------------------------------------------------------------- 1 | 2 | 3 | 4 | 5 | 6 | 7 | 8 | 9 | 10 | 11 | 12 | 13 | 14 | 15 | 16 | 17 | 18 | 19 | 24 | 25 | -------------------------------------------------------------------------------- /src/vision/realsense_camera/test/files/bat-tests/zr300_nodelet_camera_service_power_force_off_and_on_with_subscriber.test: -------------------------------------------------------------------------------- 1 | 2 | 3 | 4 | 5 | 6 | 7 | 8 | 9 | 10 | 11 | 12 | 13 | 17 | 18 | -------------------------------------------------------------------------------- /src/vision/realsense_camera/test/files/bat-tests/zr300_nodelet_camera_service_power_set_off_and_on_with_no_subscriber.test: -------------------------------------------------------------------------------- 1 | 2 | 3 | 4 | 5 | 6 | 7 | 8 | 9 | 10 | 11 | 12 | 13 | 14 | 15 | 21 | 22 | -------------------------------------------------------------------------------- /src/vision/realsense_camera/test/files/bat-tests/zr300_nodelet_transforms_enable_publish_tf.test: -------------------------------------------------------------------------------- 1 | 2 | 3 | 4 | 5 | 6 | 7 | 8 | 9 | 10 | 11 | 12 | 13 | 14 | 15 | 16 | 17 | 18 | 19 | 24 | 25 | -------------------------------------------------------------------------------- /src/vision/realsense_camera/test/files/scripts/check_librealsense_installed.py: -------------------------------------------------------------------------------- 1 | #!/usr/bin/env python 2 | """ 3 | @file check_librealsense_installed.py 4 | """ 5 | import os 6 | import sys 7 | import commands 8 | import unittest 9 | import rospy 10 | import rostest 11 | 12 | PKG = 'realsense_camera' 13 | NAME = 'check_librealsense_installed' 14 | LIB = 'librealsense.so' 15 | 16 | 17 | class CheckLibrealsenseInstalled(unittest.TestCase): 18 | """ 19 | @class CheckLibrealsenseInstalled 20 | """ 21 | 22 | def setUp(self): 23 | """ 24 | @fn setUp 25 | @param self 26 | @return 27 | """ 28 | self.success = False 29 | 30 | def test_basic_librealsense_installaton(self): 31 | """verify that librealsense library has been installed 32 | @fn test_basic_librealsense_installaton 33 | @param self 34 | @return 35 | """ 36 | rospy.init_node(NAME, anonymous=True, log_level=rospy.INFO) 37 | 38 | ros_version = commands.getoutput("rosversion -d") 39 | if os.path.exists('/opt/ros/' + ros_version + '/lib/' + LIB) == True \ 40 | or os.path.exists('/opt/ros/' + ros_version + 41 | '/lib/x86_64-linux-gnu/' + LIB) == True: 42 | self.success = True 43 | 44 | self.assert_(self.success, str(self.success)) 45 | 46 | if __name__ == '__main__': 47 | rostest.rosrun(PKG, NAME, CheckLibrealsenseInstalled, sys.argv) 48 | -------------------------------------------------------------------------------- /src/vision/realsense_camera/test/files/scripts/check_realsense_camera_nodelet_built.py: -------------------------------------------------------------------------------- 1 | #!/usr/bin/env python 2 | """ 3 | @file check_realsense_camera_nodelet_built.py 4 | """ 5 | import os 6 | import sys 7 | import commands 8 | import unittest 9 | import rospy 10 | import rostest 11 | 12 | PKG = 'realsense_camera' 13 | NAME = 'check_realsense_camera_nodelet_built' 14 | LIB = 'librealsense_camera_nodelet.so' 15 | 16 | 17 | class CheckRealsenseCameraNodeletBuilt(unittest.TestCase): 18 | """ 19 | @class CheckRealsenseCameraNodeletBuilt 20 | """ 21 | 22 | def setUp(self): 23 | """ 24 | @fn setUp 25 | @param 26 | @return 27 | """ 28 | self.success = False 29 | 30 | def test_basic_realsense_camera_wrapper_installation(self): 31 | """verify that realsense_camera has been built and installed 32 | @fn test_basic_realsense_camera_wrapper_installation 33 | @param 34 | return 35 | """ 36 | rospy.init_node(NAME, anonymous=True, log_level=rospy.INFO) 37 | 38 | lib_paths = os.environ["LD_LIBRARY_PATH"].split(":") 39 | for path in lib_paths: 40 | if os.path.exists(path + '/' + LIB) == True: 41 | self.success = True 42 | 43 | self.assert_(self.success, str(self.success)) 44 | 45 | if __name__ == '__main__': 46 | rostest.rosrun(PKG, NAME, CheckRealsenseCameraNodeletBuilt, sys.argv) 47 | -------------------------------------------------------------------------------- /src/vision/realsense_camera/test/files/scripts/libs/roscd.bash: -------------------------------------------------------------------------------- 1 | #!/bin/bash 2 | . /opt/ros/$ROS_DISTRO/share/rosbash/rosbash 3 | 4 | roscd $1 5 | 6 | base_folder=$(basename `pwd`) 7 | 8 | absolute_path=`pwd` 9 | 10 | -------------------------------------------------------------------------------- /src/vision/realsense_camera/test/files/scripts/libs/roscd_path.bash: -------------------------------------------------------------------------------- 1 | #!/bin/bash 2 | 3 | path=$(cd `dirname $0`; pwd) 4 | source $path/roscd.bash 5 | 6 | $path/roscd.bash $1 7 | echo $absolute_path 8 | 9 | -------------------------------------------------------------------------------- /src/vision/realsense_camera/test/files/scripts/libs/roscp.bash: -------------------------------------------------------------------------------- 1 | #!/bin/bash 2 | . /opt/ros/$ROS_DISTRO/share/rosbash/rosbash 3 | 4 | if [ $# != 2 ]; then 5 | echo "lack of source file or target dir..." 6 | exit 1 7 | fi 8 | 9 | roscp realsense_camera $1 $2 10 | -------------------------------------------------------------------------------- /src/vision/realsense_camera/test/files/scripts/rs_general/__init__.py: -------------------------------------------------------------------------------- 1 | #!/usr/bin/evn python 2 | -------------------------------------------------------------------------------- /src/vision/realsense_camera/test/r200_nodelet_disable_color.test: -------------------------------------------------------------------------------- 1 | 2 | 3 | 4 | 5 | 6 | 7 | 8 | 9 | 10 | 11 | 12 | 13 | 14 | 17 | 18 | -------------------------------------------------------------------------------- /src/vision/realsense_camera/test/r200_nodelet_disable_depth.test: -------------------------------------------------------------------------------- 1 | 2 | 3 | 4 | 5 | 6 | 7 | 8 | 9 | 10 | 11 | 12 | 13 | 14 | 17 | 18 | -------------------------------------------------------------------------------- /src/vision/realsense_camera/test/r200_nodelet_enable_ir.test: -------------------------------------------------------------------------------- 1 | 2 | 3 | 4 | 5 | 6 | 7 | 8 | 9 | 10 | 11 | 12 | 13 | 14 | 15 | 16 | 17 | 18 | 19 | 20 | 26 | 27 | -------------------------------------------------------------------------------- /src/vision/realsense_camera/test/r200_nodelet_rgbd.test: -------------------------------------------------------------------------------- 1 | 2 | 3 | 4 | 5 | 6 | 7 | 8 | 9 | 10 | 11 | 12 | 13 | 14 | -------------------------------------------------------------------------------- /src/vision/realsense_camera/test/sr300_nodelet_disable_color.test: -------------------------------------------------------------------------------- 1 | 2 | 3 | 4 | 5 | 6 | 7 | 8 | 9 | 10 | 11 | 12 | 13 | 14 | 17 | 18 | -------------------------------------------------------------------------------- /src/vision/realsense_camera/test/sr300_nodelet_disable_depth.test: -------------------------------------------------------------------------------- 1 | 2 | 3 | 4 | 5 | 6 | 7 | 8 | 9 | 10 | 11 | 12 | 13 | 14 | 17 | 18 | -------------------------------------------------------------------------------- /src/vision/realsense_camera/test/sr300_nodelet_enable_ir.test: -------------------------------------------------------------------------------- 1 | 2 | 3 | 4 | 5 | 6 | 7 | 8 | 9 | 10 | 11 | 12 | -------------------------------------------------------------------------------- /src/vision/realsense_camera/test/sr300_nodelet_modify_params.test: -------------------------------------------------------------------------------- 1 | 2 | 3 | 4 | 5 | 6 | 7 | 8 | 9 | 10 | 11 | 12 | 13 | 14 | 15 | 16 | -------------------------------------------------------------------------------- /src/vision/realsense_camera/test/sr300_nodelet_resolution.test: -------------------------------------------------------------------------------- 1 | 2 | 3 | 4 | 5 | 6 | 7 | -------------------------------------------------------------------------------- /src/vision/realsense_camera/test/sr300_nodelet_rgbd.test: -------------------------------------------------------------------------------- 1 | 2 | 3 | 4 | 5 | 6 | 7 | 8 | 9 | 10 | 11 | -------------------------------------------------------------------------------- /src/vision/realsense_camera/test/zr300_nodelet_default.test: -------------------------------------------------------------------------------- 1 | 2 | 3 | 4 | 5 | 6 | 7 | 8 | 9 | 10 | 11 | 12 | 13 | 14 | 19 | 20 | -------------------------------------------------------------------------------- /src/vision/usb_cam/AUTHORS.md: -------------------------------------------------------------------------------- 1 | Original Authors 2 | ---------------- 3 | 4 | * [Benjamin Pitzer] (benjamin.pitzer@bosch.com) 5 | 6 | Contributors 7 | ------------ 8 | 9 | * [Russell Toris](http://users.wpi.edu/~rctoris/) (rctoris@wpi.edu) 10 | -------------------------------------------------------------------------------- /src/vision/usb_cam/launch/start.launch: -------------------------------------------------------------------------------- 1 | 2 | 3 | 4 | 5 | 6 | 7 | 8 | 9 | 10 | 11 | 12 | 13 | -------------------------------------------------------------------------------- /src/vision/usb_cam/launch/usb_cam.launch: -------------------------------------------------------------------------------- 1 | 2 | 3 | 4 | 5 | 6 | 7 | 8 | 9 | 10 | 11 | 12 | -------------------------------------------------------------------------------- /src/vision/usb_cam/package.xml: -------------------------------------------------------------------------------- 1 | 2 | usb_cam 3 | 0.3.4 4 | A ROS Driver for V4L USB Cameras 5 | 6 | Russell Toris 7 | Benjamin Pitzer 8 | 9 | BSD 10 | 11 | http://wiki.ros.org/usb_cam 12 | https://github.com/bosch-ros-pkg/usb_cam/issues 13 | https://github.com/bosch-ros-pkg/usb_cam 14 | 15 | catkin 16 | 17 | image_transport 18 | roscpp 19 | std_msgs 20 | std_srvs 21 | sensor_msgs 22 | ffmpeg 23 | camera_info_manager 24 | 25 | image_transport 26 | roscpp 27 | std_msgs 28 | std_srvs 29 | sensor_msgs 30 | ffmpeg 31 | camera_info_manager 32 | v4l-utils 33 | 34 | -------------------------------------------------------------------------------- /src/vision/usb_cam/src/LICENSE: -------------------------------------------------------------------------------- 1 | Video for Linux Two API Specification 2 | Revision 0.24 3 | Michael H Schimek 4 | Bill Dirks 5 | Hans Verkuil 6 | Martin Rubli 7 | 8 | Copyright © 1999, 2000, 2001, 2002, 2003, 2004, 2005, 2006, 2007, 2008 Bill Dirks, Michael H. Schimek, Hans Verkuil, Martin Rubli 9 | 10 | This document is copyrighted © 1999-2008 by Bill Dirks, Michael H. Schimek, Hans Verkuil and Martin Rubli. 11 | 12 | Permission is granted to copy, distribute and/or modify this document under the terms of the GNU Free Documentation License, Version 1.1 or any later version published by the Free Software Foundation; with no Invariant Sections, with no Front-Cover Texts, and with no Back-Cover Texts. A copy of the license is included in the appendix entitled "GNU Free Documentation License". 13 | 14 | Programming examples can be used and distributed without restrictions. 15 | --------------------------------------------------------------------------------