Savety safe
106
src/dcaiti_control/description/assets/ft24_wheel.dae
Normal file
53
src/dcaiti_control/description/bbox_camera.xacro
Normal file
@ -0,0 +1,53 @@
|
||||
<?xml version="1.0"?>
|
||||
<robot xmlns:xacro="http://www.ros.org/wiki/xacro" >
|
||||
|
||||
<joint name="camera_joint" type="fixed">
|
||||
<parent link="chassis"/>
|
||||
<child link="camera_link"/>
|
||||
<origin xyz="0 0 1" rpy="0 0 0"/>
|
||||
</joint>
|
||||
|
||||
<link name="camera_link">
|
||||
<visual>
|
||||
<geometry>
|
||||
<box size="0.025 0.09 0.025"/>
|
||||
</geometry>
|
||||
<material name="black"/>
|
||||
</visual>
|
||||
</link>
|
||||
|
||||
|
||||
<joint name="camera_optical_joint" type="fixed">
|
||||
<parent link="camera_link"/>
|
||||
<child link="camera_link_optical"/>
|
||||
<origin xyz="0 0 0" rpy="${-pi/2} 0 ${-pi/2}"/>
|
||||
</joint>
|
||||
|
||||
<link name="camera_link_optical"></link>
|
||||
|
||||
|
||||
|
||||
<gazebo reference="camera_link">
|
||||
<material>Gazebo/Black</material>
|
||||
<sensor name="boundingbox_camera" type="boundingbox_camera">
|
||||
<ignition_frame_id>camera_link_optical</ignition_frame_id>
|
||||
<topic>boxes</topic>
|
||||
<camera>
|
||||
<box_type>2d</box_type>
|
||||
<horizontal_fov>1.047</horizontal_fov>
|
||||
<image>
|
||||
<width>640</width>
|
||||
<height>480</height>
|
||||
</image>
|
||||
<clip>
|
||||
<near>0.01</near>
|
||||
<far>60</far>
|
||||
</clip>
|
||||
</camera>
|
||||
<always_on>1</always_on>
|
||||
<update_rate>50</update_rate>
|
||||
<visualize>false</visualize>
|
||||
</sensor>
|
||||
</gazebo>
|
||||
|
||||
</robot>
|
@ -1,55 +0,0 @@
|
||||
<?xml version="1.0"?>
|
||||
<robot xmlns:xacro="http://www.ros.org/wiki/xacro" >
|
||||
|
||||
<joint name="camera_joint" type="fixed">
|
||||
<parent link="chassis"/>
|
||||
<child link="camera_link"/>
|
||||
<origin xyz="0.305 0 0.08" rpy="0 0 0"/>
|
||||
</joint>
|
||||
|
||||
<link name="camera_link">
|
||||
<visual>
|
||||
<geometry>
|
||||
<box size="0.010 0.03 0.03"/>
|
||||
</geometry>
|
||||
<material name="red"/>
|
||||
</visual>
|
||||
</link>
|
||||
|
||||
|
||||
<joint name="camera_optical_joint" type="fixed">
|
||||
<parent link="camera_link"/>
|
||||
<child link="camera_link_optical"/>
|
||||
<origin xyz="0 0 0" rpy="${-pi/2} 0 ${-pi/2}"/>
|
||||
</joint>
|
||||
|
||||
<link name="camera_link_optical"></link>
|
||||
|
||||
|
||||
|
||||
<gazebo reference="camera_link">
|
||||
<material>Gazebo/Red</material>
|
||||
|
||||
<sensor name="camera" type="camera">
|
||||
<pose> 0 0 0 0 0 0 </pose>
|
||||
<visualize>true</visualize>
|
||||
<update_rate>10</update_rate>
|
||||
<camera>
|
||||
<horizontal_fov>1.089</horizontal_fov>
|
||||
<image>
|
||||
<format>R8G8B8</format>
|
||||
<width>640</width>
|
||||
<height>480</height>
|
||||
</image>
|
||||
<clip>
|
||||
<near>0.05</near>
|
||||
<far>8.0</far>
|
||||
</clip>
|
||||
</camera>
|
||||
<plugin name="camera_controller" filename="libgazebo_ros_camera.so">
|
||||
<frame_name>camera_link_optical</frame_name>
|
||||
</plugin>
|
||||
</sensor>
|
||||
</gazebo>
|
||||
|
||||
</robot>
|
@ -1,36 +0,0 @@
|
||||
<?xml version="1.0"?>
|
||||
<robot xmlns:xacro="http://www.ros.org/wiki/xacro">
|
||||
|
||||
<gazebo>
|
||||
<plugin name='diff_drive' filename='libgazebo_ros_diff_drive.so'>
|
||||
|
||||
<update_rate>30</update_rate>
|
||||
<!-- Wheel Information -->
|
||||
<left_joint>left_wheel_joint</left_joint>
|
||||
<right_joint>right_wheel_joint</right_joint>
|
||||
<wheel_separation>0.35</wheel_separation>
|
||||
<wheel_diameter>0.1</wheel_diameter>
|
||||
|
||||
|
||||
<!-- Limits -->
|
||||
<max_wheel_torque>200</max_wheel_torque>
|
||||
<max_wheel_acceleration>10.0</max_wheel_acceleration>
|
||||
|
||||
|
||||
<!-- Output -->
|
||||
<command_topic>cmd_vel</command_topic>
|
||||
|
||||
<!-- output -->
|
||||
<publish_odom>true</publish_odom>
|
||||
<publish_odom_tf>true</publish_odom_tf>
|
||||
<publish_wheel_tf>true</publish_wheel_tf>
|
||||
|
||||
<odometry_topic>odom</odometry_topic>
|
||||
<odometry_frame>odom</odometry_frame>
|
||||
<robot_base_frame>base_link</robot_base_frame>
|
||||
|
||||
|
||||
</plugin>
|
||||
</gazebo>
|
||||
|
||||
</robot>
|
@ -36,5 +36,42 @@
|
||||
</inertial>
|
||||
</xacro:macro>
|
||||
|
||||
<!-- Math constants -->
|
||||
<xacro:property name="math_pi" value="3.141592653589793" />
|
||||
<xacro:property name="math_pi_over_2" value="1.5707963267948966" />
|
||||
<xacro:property name="math_pi_over_4" value="0.785398163397448" />
|
||||
|
||||
<!-- Inertial for solid cuboid with dimensions x y z -->
|
||||
<xacro:macro name="solid_cuboid_inertial" params="rpy xyz mass x y z">
|
||||
<inertial>
|
||||
<origin rpy="${rpy}" xyz="${xyz}"/>
|
||||
<mass value="${mass}" />
|
||||
<inertia
|
||||
ixx="${mass * (y * y + z * z) / 12.0}" ixy="0.0" ixz="0.0"
|
||||
iyy="${mass * (x * x + z * z) / 12.0}" iyz="0.0"
|
||||
izz="${mass * (x * x + y * y) / 12.0}" />
|
||||
</inertial>
|
||||
</xacro:macro>
|
||||
|
||||
<!-- Inertial for solid cylinder with radius and length aligned to z-axis -->
|
||||
<xacro:macro name="solid_cylinder_inertial" params="rpy xyz mass radius length">
|
||||
<inertial>
|
||||
<origin rpy="${rpy}" xyz="${xyz}"/>
|
||||
<mass value="${mass}" />
|
||||
<inertia
|
||||
ixx="${mass * (3.0 * radius * radius + length * length) / 12.0}" ixy="0.0" ixz="0.0"
|
||||
iyy="${mass * (3.0 * radius * radius + length * length) / 12.0}" iyz="0.0"
|
||||
izz="${mass * (radius * radius) / 2.0}" />
|
||||
</inertial>
|
||||
</xacro:macro>
|
||||
|
||||
<!-- A null inertial - used in placeholder links to esure the model will work in Gazebo -->
|
||||
<xacro:macro name="null_inertial">
|
||||
<inertial>
|
||||
<mass value="0.001"/>
|
||||
<inertia ixx="0.001" ixy="0" ixz="0" iyy="0.001" iyz="0" izz="0.001"/>
|
||||
</inertial>
|
||||
</xacro:macro>
|
||||
|
||||
|
||||
</robot>
|
@ -16,9 +16,28 @@
|
||||
<xacro:arg name="wheel_radius" default="0.05"/>
|
||||
<xacro:arg name="wheel_width" default="0.02"/>
|
||||
|
||||
<xacro:arg name="base_height" default="0.1"/>
|
||||
<xacro:arg name="base_width" default="0.2"/>
|
||||
<xacro:arg name="base_length" default="0.2"/>
|
||||
<!-- Math constants -->
|
||||
<xacro:property name="deg_to_rad" value="0.01745329251994329577"/>
|
||||
|
||||
<!-- Robot base dimensions -->
|
||||
<xacro:property name="base_length" value="10.0" />
|
||||
<xacro:property name="base_width" value="10.0" />
|
||||
<xacro:property name="base_height" value="0.1" />
|
||||
<xacro:property name="base_mass" value="5.0" />
|
||||
|
||||
<!-- Wheel link dimensions -->
|
||||
<xacro:property name="wheel_radius" value="0.1" />
|
||||
<xacro:property name="wheel_thickness" value="0.08" />
|
||||
<xacro:property name="wheel_mass" value="1" />
|
||||
|
||||
<!-- Steering link dimensions -->
|
||||
<xacro:property name="steer_radius" value="0.05" />
|
||||
<xacro:property name="steer_thickness" value="0.02" />
|
||||
<xacro:property name="steer_mass" value="1" />
|
||||
|
||||
<!-- Axle positions -->
|
||||
<xacro:property name="axle_offset" value="-0.5" />
|
||||
<xacro:property name="steer_offset" value="-0.5" />
|
||||
|
||||
|
||||
|
||||
@ -28,22 +47,13 @@
|
||||
<!-- Include the inertial macros -->
|
||||
<xacro:include filename="inertial_macros.xacro"/>
|
||||
<!-- Include the gazebo control -->
|
||||
<xacro:if value="$(arg use_ros2_control)">
|
||||
<xacro:if value="$(arg use_sim)">
|
||||
<xacro:include filename="ros2_control.xacro" />
|
||||
</xacro:if>
|
||||
<xacro:unless value="$(arg use_sim)">
|
||||
<xacro:include filename="real_robot_control.xacro" />
|
||||
</xacro:unless>
|
||||
<xacro:if value="$(arg use_sim)">
|
||||
<xacro:include filename="ros2_control.xacro" />
|
||||
</xacro:if>
|
||||
<xacro:unless value="$(arg use_ros2_control)">
|
||||
<xacro:include filename="gazebo_control.xacro" />
|
||||
<xacro:unless value="$(arg use_sim)">
|
||||
<xacro:include filename="real_robot_control.xacro" />
|
||||
</xacro:unless>
|
||||
|
||||
<!-- Sensors -->
|
||||
<xacro:include filename="camera.xacro" />
|
||||
<xacro:include filename="lidar.xacro" />
|
||||
|
||||
<xacro:include filename="robot_core.xacro" />
|
||||
|
||||
</robot>
|
@ -1,6 +1,8 @@
|
||||
<?xml version="1.0"?>
|
||||
<robot xmlns:xacro="http://www.ros.org/wiki/xacro">
|
||||
|
||||
<xacro:include filename="wheel.xacro" />
|
||||
|
||||
<link name="base_link">
|
||||
</link>
|
||||
|
||||
@ -36,131 +38,79 @@
|
||||
</gazebo>
|
||||
|
||||
|
||||
<!-- LEFT WHEEL LINK -->
|
||||
<!-- Front steer and rear wheel joints required for ackermann_steering_controller -->
|
||||
<xacro:front_steer
|
||||
name="front"
|
||||
parent="base"
|
||||
steer_radius="${steer_radius}"
|
||||
steer_thickness="${steer_thickness}"
|
||||
steer_mass="${steer_mass}"
|
||||
base_length="${base_length}"
|
||||
base_width="${base_width}"
|
||||
axle_offset="${axle_offset}"
|
||||
steer_height="${wheel_radius+steer_offset}">
|
||||
</xacro:front_steer>
|
||||
|
||||
<link name="left_wheel">
|
||||
<visual>
|
||||
<geometry>
|
||||
<cylinder radius="${0.31/(2*pi)}" length="0.04"/>
|
||||
</geometry>
|
||||
<material name="blue"/>
|
||||
</visual>
|
||||
<collision>
|
||||
<geometry>
|
||||
<!-- Better collosion behaviour than a cylinder -->
|
||||
<sphere radius="${0.31/(2*pi)}"/>
|
||||
</geometry>
|
||||
</collision>
|
||||
<xacro:inertial_cylinder mass="0.1" radius="${0.31/(2*pi)}" length="0.04">
|
||||
<origin xyz="0 0 0" rpy="0 0 0"/>
|
||||
</xacro:inertial_cylinder>
|
||||
</link>
|
||||
|
||||
<joint name="left_wheel_joint" type="continuous">
|
||||
<parent link="base_link"/>
|
||||
<child link="left_wheel"/>
|
||||
<origin xyz="0 0.1075 0" rpy="-${pi/2} 0 0" />
|
||||
<axis xyz="0 0 1"/>
|
||||
</joint>
|
||||
<xacro:rear_wheel
|
||||
name="rear"
|
||||
parent="base"
|
||||
wheel_radius="${wheel_radius/4}"
|
||||
wheel_thickness="${wheel_thickness/2}"
|
||||
wheel_mass="${wheel_mass/32}">
|
||||
<origin xyz="${-base_length/2+axle_offset} 0 0" rpy="${-90 * deg_to_rad} 0 0"/>
|
||||
</xacro:rear_wheel>
|
||||
|
||||
<gazebo reference="left_wheel">
|
||||
<material>Gazebo/Grey</material>
|
||||
</gazebo>
|
||||
<!-- Steerable front wheels -->
|
||||
<xacro:front_wheel_lr
|
||||
name="front_right"
|
||||
parent="base"
|
||||
reflect="-1"
|
||||
wheel_radius="${wheel_radius}"
|
||||
wheel_thickness="${wheel_thickness}"
|
||||
wheel_mass="${wheel_mass}"
|
||||
steer_radius="${steer_radius}"
|
||||
steer_thickness="${steer_thickness}"
|
||||
steer_mass="${steer_mass}"
|
||||
base_length="${base_length}"
|
||||
base_width="${base_width}"
|
||||
axle_offset="${axle_offset}"
|
||||
steer_height="${wheel_radius+steer_offset}">
|
||||
</xacro:front_wheel_lr>
|
||||
<xacro:front_wheel_lr
|
||||
name="front_left"
|
||||
parent="base"
|
||||
reflect="1"
|
||||
wheel_radius="${wheel_radius}"
|
||||
wheel_thickness="${wheel_thickness}"
|
||||
wheel_mass="${wheel_mass}"
|
||||
steer_radius="${steer_radius}"
|
||||
steer_thickness="${steer_thickness}"
|
||||
steer_mass="${steer_mass}"
|
||||
base_length="${base_length}"
|
||||
base_width="${base_width}"
|
||||
axle_offset="${axle_offset}"
|
||||
steer_height="${wheel_radius+steer_offset}">
|
||||
</xacro:front_wheel_lr>
|
||||
|
||||
<!-- RIGHT WHEEL LINK -->
|
||||
|
||||
<link name="right_wheel">
|
||||
<visual>
|
||||
<geometry>
|
||||
<!-- Better collosion behaviour than a cylinder -->
|
||||
<cylinder radius="${0.31/(2*pi)}" length="0.04"/>
|
||||
</geometry>
|
||||
<material name="blue"/>
|
||||
</visual>
|
||||
<collision>
|
||||
<geometry>
|
||||
<sphere radius="${0.31/(2*pi)}" />
|
||||
</geometry>
|
||||
</collision>
|
||||
<xacro:inertial_cylinder mass="0.1" radius="${0.31/(2*pi)}" length="0.04">
|
||||
<origin xyz="0 0 0" rpy="0 0 0"/>
|
||||
</xacro:inertial_cylinder>
|
||||
</link>
|
||||
|
||||
<joint name="right_wheel_joint" type="continuous">
|
||||
<parent link="base_link"/>
|
||||
<child link="right_wheel"/>
|
||||
<origin xyz="0 -0.1075 0" rpy="${pi/2} 0 0" />
|
||||
<axis xyz="0 0 -1"/>
|
||||
</joint>
|
||||
|
||||
<gazebo reference="right_wheel">
|
||||
<material>Gazebo/Grey</material>
|
||||
</gazebo>
|
||||
|
||||
<!-- CASTER WHEEL LINK Front -->
|
||||
|
||||
<joint name="caster_wheel_joint_front" type="fixed">
|
||||
<parent link="chassis"/>
|
||||
<child link="caster_wheel_front"/>
|
||||
<origin xyz="0.1 0 0"/>
|
||||
</joint>
|
||||
|
||||
|
||||
<link name="caster_wheel_front">
|
||||
<visual>
|
||||
<geometry>
|
||||
<sphere radius="${0.31/(2*pi)}"/>
|
||||
</geometry>
|
||||
<material name="black"/>
|
||||
</visual>
|
||||
<collision>
|
||||
<geometry>
|
||||
<sphere radius="${0.31/(2*pi)}"/>
|
||||
</geometry>
|
||||
</collision>
|
||||
<xacro:inertial_sphere mass="0.1" radius="${0.31/(2*pi)}">
|
||||
<origin xyz="0 0 0" rpy="0 0 0"/>
|
||||
</xacro:inertial_sphere>
|
||||
</link>
|
||||
|
||||
<gazebo reference="caster_wheel_front">
|
||||
<material>Gazebo/Black</material>
|
||||
<mu1 value="0.001"/>
|
||||
<mu2 value="0.001"/>
|
||||
</gazebo>
|
||||
|
||||
<!-- CASTER WHEEL LINK BACK-->
|
||||
|
||||
<joint name="caster_wheel_joint_back" type="fixed">
|
||||
<parent link="chassis"/>
|
||||
<child link="caster_wheel_back"/>
|
||||
<origin xyz="-0.1 0 0"/>
|
||||
</joint>
|
||||
|
||||
|
||||
<link name="caster_wheel_back">
|
||||
<visual>
|
||||
<geometry>
|
||||
<sphere radius="${0.31/(2*pi)}"/>
|
||||
</geometry>
|
||||
<material name="black"/>
|
||||
</visual>
|
||||
<collision>
|
||||
<geometry>
|
||||
<sphere radius="${0.31/(2*pi)}"/>
|
||||
</geometry>
|
||||
</collision>
|
||||
<xacro:inertial_sphere mass="0.1" radius="${0.31/(2*pi)}">
|
||||
<origin xyz="0 0 0" rpy="0 0 0"/>
|
||||
</xacro:inertial_sphere>
|
||||
</link>
|
||||
|
||||
<gazebo reference="caster_wheel_back">
|
||||
<material>Gazebo/Black</material>
|
||||
<mu1 value="0.001"/>
|
||||
<mu2 value="0.001"/>
|
||||
</gazebo>
|
||||
<!-- Rear wheels -->
|
||||
<xacro:rear_wheel_lr
|
||||
name="rear_right"
|
||||
parent="base"
|
||||
reflect="-1"
|
||||
wheel_radius="${wheel_radius}"
|
||||
wheel_thickness="${wheel_thickness}"
|
||||
wheel_mass="${wheel_mass}">
|
||||
<origin xyz="${-base_length/2+axle_offset} ${-base_width/2-axle_offset} 0" rpy="${-90 * deg_to_rad} 0 0"/>
|
||||
</xacro:rear_wheel_lr>
|
||||
<xacro:rear_wheel_lr
|
||||
name="rear_left"
|
||||
parent="base"
|
||||
reflect="1"
|
||||
wheel_radius="${wheel_radius}"
|
||||
wheel_thickness="${wheel_thickness}"
|
||||
wheel_mass="${wheel_mass}">
|
||||
<origin xyz="${-base_length/2+axle_offset} ${+base_width/2+axle_offset} 0" rpy="${-90 * deg_to_rad} 0 0"/>
|
||||
</xacro:rear_wheel_lr>
|
||||
|
||||
|
||||
</robot>
|
@ -1,28 +1,32 @@
|
||||
<?xml version="1.0"?>
|
||||
<robot xmlns:xacro="http://www.ros.org/wiki/xacro" >
|
||||
<ros2_control name="GazeboSystem" type="system">
|
||||
<ros2_control name="GazeboSimSystem" type="system">
|
||||
<hardware>
|
||||
<plugin>gazebo_ros2_control/GazeboSystem</plugin>
|
||||
<plugin>ign_ros2_control/IgnitionSystem</plugin>
|
||||
</hardware>
|
||||
<joint name="left_wheel_joint">
|
||||
<command_interface name="velocity">
|
||||
<param name="min">-0.5</param>
|
||||
<param name="max">0.5</param>
|
||||
</command_interface>
|
||||
<state_interface name="position" />
|
||||
<state_interface name="velocity" />
|
||||
<joint name="rear_right_wheel_joint">
|
||||
<command_interface name="velocity"/>
|
||||
<state_interface name="position"/>
|
||||
<state_interface name="velocity"/>
|
||||
</joint>
|
||||
<joint name="right_wheel_joint">
|
||||
<command_interface name="velocity">
|
||||
<param name="min">-0.5</param>
|
||||
<param name="max">0.5</param>
|
||||
</command_interface>
|
||||
<state_interface name="velocity" />
|
||||
<state_interface name="position" />
|
||||
<joint name="rear_left_wheel_joint">
|
||||
<command_interface name="velocity"/>
|
||||
<state_interface name="position"/>
|
||||
<state_interface name="velocity"/>
|
||||
</joint>
|
||||
<joint name="front_left_steer_joint">
|
||||
<command_interface name="position"/>
|
||||
<state_interface name="position"/>
|
||||
<state_interface name="velocity"/>
|
||||
</joint>
|
||||
<joint name="front_right_steer_joint">
|
||||
<command_interface name="position"/>
|
||||
<state_interface name="position"/>
|
||||
<state_interface name="velocity"/>
|
||||
</joint>
|
||||
</ros2_control>
|
||||
<gazebo>
|
||||
<plugin filename="libgazebo_ros2_control.so" name="gazebo_ros2_control">
|
||||
<plugin filename="libign_ros2_control-system.so" name="ign_ros2_control::IgnitionROS2ControlPlugin">
|
||||
<parameters>$(find dcaiti_control)/config/dcaiti_config.yml</parameters>
|
||||
<parameters>$(find dcaiti_control)/config/gaz_ros2_ctl_sim.yml</parameters>
|
||||
</plugin>
|
||||
|
158
src/dcaiti_control/description/steerbot.urdf.xacro
Normal file
@ -0,0 +1,158 @@
|
||||
<?xml version="1.0"?>
|
||||
<!--
|
||||
Robot model adapted from https://github.com/CIR-KIT/steer_drive_ros/blob/kinetic-devel/steer_drive_controller/test/common/urdf/steerbot.xacro
|
||||
|
||||
Modifications:
|
||||
Remove base_footprint link. Useful for navigation but not necessary for a simple example.
|
||||
Added materials for URDF
|
||||
Updated inertials
|
||||
|
||||
Geometry:
|
||||
The Ackermann steering controllers require the longitudinal
|
||||
separation between the front and back wheel axes and the
|
||||
lateral separation between the left and right front steering axes.
|
||||
|
||||
For this model:
|
||||
wheel_separation_h = base_length - 2 * axle_offset = 0.4
|
||||
wheel_separation_w = base_width + 2 * axle_offset = 0.4
|
||||
-->
|
||||
<robot name="steer_bot" xmlns:xacro="http://wiki.ros.org/xacro">
|
||||
<!-- Include xacro for inertials, materials and wheels -->
|
||||
<xacro:include filename="wheel.xacro"/>
|
||||
<xacro:include filename="inertial_macros.xacro"/>
|
||||
|
||||
<xacro:property name="robot_namespace" value="/steer_bot"/>
|
||||
|
||||
<!-- Gazebo plugins -->
|
||||
<gazebo>
|
||||
<!-- Load ros_control plugin using the steer_bot_hardware_gazebo
|
||||
implementation of the hardware_interface::RobotHW -->
|
||||
<plugin filename="libign_ros2_control-system.so" name="ign_ros2_control::IgnitionROS2ControlPlugin">
|
||||
<robotNamespace>${robot_namespace}</robotNamespace>
|
||||
</plugin>
|
||||
</gazebo>
|
||||
|
||||
<!-- Math constants -->
|
||||
<xacro:property name="deg_to_rad" value="0.01745329251994329577"/>
|
||||
|
||||
<!-- Robot base dimensions -->
|
||||
<xacro:property name="base_length" value="10.0" />
|
||||
<xacro:property name="base_width" value="10.0" />
|
||||
<xacro:property name="base_height" value="0.1" />
|
||||
<xacro:property name="base_mass" value="5.0" />
|
||||
|
||||
<!-- Wheel link dimensions -->
|
||||
<xacro:property name="wheel_radius" value="0.1" />
|
||||
<xacro:property name="wheel_thickness" value="0.08" />
|
||||
<xacro:property name="wheel_mass" value="1" />
|
||||
|
||||
<!-- Steering link dimensions -->
|
||||
<xacro:property name="steer_radius" value="0.05" />
|
||||
<xacro:property name="steer_thickness" value="0.02" />
|
||||
<xacro:property name="steer_mass" value="1" />
|
||||
|
||||
<!-- Axle positions -->
|
||||
<xacro:property name="axle_offset" value="-0.5" />
|
||||
<xacro:property name="steer_offset" value="-0.5" />
|
||||
|
||||
<!-- Base link -->
|
||||
<link name="base_link">
|
||||
<visual>
|
||||
<origin xyz="0 0 0" rpy="0 0 0"/>
|
||||
<geometry>
|
||||
<box size="1 1 1"/>
|
||||
</geometry>
|
||||
<material name="green" />
|
||||
</visual>
|
||||
<collision>
|
||||
<origin xyz="0 0 0" rpy="0 0 0"/>
|
||||
<geometry>
|
||||
<box size="1 1 1"/>
|
||||
</geometry>
|
||||
</collision>
|
||||
<xacro:solid_cuboid_inertial
|
||||
rpy="0 0 0" xyz="0 0 0"
|
||||
mass="${base_mass}"
|
||||
x="${base_length}" y="${base_width}" z="${base_height}" />
|
||||
</link>
|
||||
|
||||
<!-- Front steer and rear wheel joints required for ackermann_steering_controller -->
|
||||
<xacro:front_steer
|
||||
name="front"
|
||||
parent="base"
|
||||
steer_radius="${steer_radius}"
|
||||
steer_thickness="${steer_thickness}"
|
||||
steer_mass="${steer_mass}"
|
||||
base_length="${base_length}"
|
||||
base_width="${base_width}"
|
||||
axle_offset="${axle_offset}"
|
||||
steer_height="${wheel_radius+steer_offset}">
|
||||
</xacro:front_steer>
|
||||
|
||||
<xacro:rear_wheel
|
||||
name="rear"
|
||||
parent="base"
|
||||
wheel_radius="${wheel_radius/4}"
|
||||
wheel_thickness="${wheel_thickness/2}"
|
||||
wheel_mass="${wheel_mass/32}">
|
||||
<origin xyz="${-base_length/2+axle_offset} 0 0" rpy="${-90 * deg_to_rad} 0 0"/>
|
||||
</xacro:rear_wheel>
|
||||
|
||||
<!-- Steerable front wheels -->
|
||||
<xacro:front_wheel_lr
|
||||
name="front_right"
|
||||
parent="base"
|
||||
reflect="-1"
|
||||
wheel_radius="${wheel_radius}"
|
||||
wheel_thickness="${wheel_thickness}"
|
||||
wheel_mass="${wheel_mass}"
|
||||
steer_radius="${steer_radius}"
|
||||
steer_thickness="${steer_thickness}"
|
||||
steer_mass="${steer_mass}"
|
||||
base_length="${base_length}"
|
||||
base_width="${base_width}"
|
||||
axle_offset="${axle_offset}"
|
||||
steer_height="${wheel_radius+steer_offset}">
|
||||
</xacro:front_wheel_lr>
|
||||
<xacro:front_wheel_lr
|
||||
name="front_left"
|
||||
parent="base"
|
||||
reflect="1"
|
||||
wheel_radius="${wheel_radius}"
|
||||
wheel_thickness="${wheel_thickness}"
|
||||
wheel_mass="${wheel_mass}"
|
||||
steer_radius="${steer_radius}"
|
||||
steer_thickness="${steer_thickness}"
|
||||
steer_mass="${steer_mass}"
|
||||
base_length="${base_length}"
|
||||
base_width="${base_width}"
|
||||
axle_offset="${axle_offset}"
|
||||
steer_height="${wheel_radius+steer_offset}">
|
||||
</xacro:front_wheel_lr>
|
||||
|
||||
<!-- Rear wheels -->
|
||||
<xacro:rear_wheel_lr
|
||||
name="rear_right"
|
||||
parent="base"
|
||||
reflect="-1"
|
||||
wheel_radius="${wheel_radius}"
|
||||
wheel_thickness="${wheel_thickness}"
|
||||
wheel_mass="${wheel_mass}">
|
||||
<origin xyz="${-base_length/2+axle_offset} ${-base_width/2-axle_offset} 0" rpy="${-90 * deg_to_rad} 0 0"/>
|
||||
</xacro:rear_wheel_lr>
|
||||
<xacro:rear_wheel_lr
|
||||
name="rear_left"
|
||||
parent="base"
|
||||
reflect="1"
|
||||
wheel_radius="${wheel_radius}"
|
||||
wheel_thickness="${wheel_thickness}"
|
||||
wheel_mass="${wheel_mass}">
|
||||
<origin xyz="${-base_length/2+axle_offset} ${+base_width/2+axle_offset} 0" rpy="${-90 * deg_to_rad} 0 0"/>
|
||||
</xacro:rear_wheel_lr>
|
||||
|
||||
<!-- Colour -->
|
||||
<gazebo reference="base_link">
|
||||
<material>Gazebo/Green</material>
|
||||
</gazebo>
|
||||
|
||||
</robot>
|
329
src/dcaiti_control/description/wheel.xacro
Normal file
@ -0,0 +1,329 @@
|
||||
<?xml version="1.0"?>
|
||||
<!--
|
||||
Robot model adapted from https://github.com/CIR-KIT/steer_drive_ros/blob/kinetic-devel/steer_drive_controller/test/common/urdf/wheel.xacro
|
||||
|
||||
Modifications:
|
||||
<transmissions> elements have been updated and added to 'front_steer'.
|
||||
Update inertials.
|
||||
Remove dependency on externally defined parameters.
|
||||
-->
|
||||
<robot name="wheel" xmlns:xacro="http://wiki.ros.org/xacro">
|
||||
<!-- Include xacro for materials and inertials -->
|
||||
|
||||
<!-- Properties -->
|
||||
<xacro:property name="steer_effort" value="100.0"/>
|
||||
<xacro:property name="steer_velocity" value="20.0"/>
|
||||
<xacro:property name="steer_limit_deg" value="45.0"/>
|
||||
|
||||
<!-- Bicycle model front steering link (required for steer_drive_controller) -->
|
||||
<xacro:macro name="front_steer"
|
||||
params="
|
||||
name
|
||||
parent
|
||||
steer_radius
|
||||
steer_thickness
|
||||
steer_mass
|
||||
base_length
|
||||
base_width
|
||||
axle_offset
|
||||
steer_height">
|
||||
<link name="${name}_steer_link">
|
||||
<visual>
|
||||
<origin xyz="0 0 0" rpy="0 0 0"/>
|
||||
<geometry>
|
||||
<cylinder radius="${steer_radius}" length="${steer_thickness}"/>
|
||||
</geometry>
|
||||
<material name="yellow" />
|
||||
</visual>
|
||||
<collision>
|
||||
<origin xyz="0 0 0" rpy="0 0 0"/>
|
||||
<geometry>
|
||||
<cylinder radius="${steer_radius}" length="${steer_thickness}"/>
|
||||
</geometry>
|
||||
</collision>
|
||||
<xacro:solid_cylinder_inertial
|
||||
rpy="0 0 0" xyz="0 0 0"
|
||||
mass="${steer_mass}"
|
||||
radius="${steer_radius}" length="${steer_thickness}" />
|
||||
</link>
|
||||
|
||||
<joint name="${name}_steer_joint" type="revolute">
|
||||
<parent link="${parent}_link"/>
|
||||
<child link="${name}_steer_link"/>
|
||||
<origin xyz="${base_length/2-axle_offset} 0 ${steer_height}" rpy="0 0 0"/>
|
||||
<axis xyz="0 0 1"/>
|
||||
<limit effort="${steer_effort}"
|
||||
lower="${-180.0 * deg_to_rad}" upper="${180.0 * deg_to_rad}"
|
||||
velocity="${steer_velocity}"/>
|
||||
</joint>
|
||||
|
||||
<transmission name="${name}_steer_joint_trans">
|
||||
<type>transmission_interface/SimpleTransmission</type>
|
||||
<actuator name="${name}_steer_joint_motor">
|
||||
<mechanicalReduction>1</mechanicalReduction>
|
||||
<hardwareInterface>hardware_interface/PositionJointInterface</hardwareInterface>
|
||||
</actuator>
|
||||
<joint name="${name}_steer_joint">
|
||||
<hardwareInterface>hardware_interface/PositionJointInterface</hardwareInterface>
|
||||
</joint>
|
||||
</transmission>
|
||||
|
||||
<gazebo reference="${name}_steer_link">
|
||||
<material>Gazebo/Yellow</material>
|
||||
</gazebo>
|
||||
</xacro:macro>
|
||||
|
||||
<!-- Car steering model front (steerable) wheel links (left/right) -->
|
||||
<xacro:macro name="front_wheel_lr"
|
||||
params="
|
||||
name
|
||||
parent
|
||||
reflect
|
||||
wheel_radius
|
||||
wheel_thickness
|
||||
wheel_mass
|
||||
steer_radius
|
||||
steer_thickness
|
||||
steer_mass
|
||||
base_length
|
||||
base_width
|
||||
axle_offset
|
||||
steer_height">
|
||||
<link name="${name}_steer_link">
|
||||
<visual>
|
||||
<origin xyz="0 0 0" rpy="0 0 0"/>
|
||||
<geometry>
|
||||
<cylinder radius="${steer_radius}" length="${steer_thickness}"/>
|
||||
</geometry>
|
||||
<material name="blue" />
|
||||
</visual>
|
||||
<collision>
|
||||
<origin xyz="0 0 0" rpy="0 0 0"/>
|
||||
<geometry>
|
||||
<cylinder radius="${steer_radius}" length="${wheel_thickness}"/>
|
||||
</geometry>
|
||||
</collision>
|
||||
<xacro:solid_cylinder_inertial
|
||||
rpy="0 0 0" xyz="0 0 0"
|
||||
mass="${steer_mass}"
|
||||
radius="${steer_radius}" length="${steer_thickness}" />
|
||||
</link>
|
||||
|
||||
<joint name="${name}_steer_joint" type="revolute">
|
||||
<parent link="${parent}_link"/>
|
||||
<child link="${name}_steer_link"/>
|
||||
<origin xyz="${base_length/2-axle_offset} ${reflect*(base_width/2+axle_offset)} ${steer_height}" rpy="0 0 0"/>
|
||||
<axis xyz="0 0 1"/>
|
||||
<limit effort="${steer_effort}"
|
||||
lower="${steer_limit_deg * deg_to_rad * -1.0}" upper="${steer_limit_deg * deg_to_rad}"
|
||||
velocity="${steer_velocity}"/>
|
||||
</joint>
|
||||
|
||||
<link name="${name}_wheel_link">
|
||||
<collision>
|
||||
<origin xyz="0 0 0" rpy="0 0 0"/>
|
||||
<geometry>
|
||||
<cylinder radius="${wheel_radius}" length="${wheel_thickness}"/>
|
||||
</geometry>
|
||||
</collision>
|
||||
<visual>
|
||||
<origin xyz="0 0 0" rpy="${-pi/2} ${(reflect * pi/2) + pi/2} 0"/>
|
||||
<geometry>
|
||||
<mesh filename="file://$(find dcaiti_control)/description/assets/ft24_wheel_simplified.dae" />
|
||||
</geometry>
|
||||
<material name="grey" />
|
||||
</visual>
|
||||
<xacro:solid_cylinder_inertial
|
||||
rpy="0 0 0" xyz="0 0 0"
|
||||
mass="${wheel_mass}"
|
||||
radius="${wheel_radius}" length="${wheel_thickness}" />
|
||||
</link>
|
||||
|
||||
<joint name="${name}_wheel_joint" type="continuous">
|
||||
<parent link="${name}_steer_link"/>
|
||||
<child link="${name}_wheel_link"/>
|
||||
<origin xyz="0 0 ${-steer_height}" rpy="${-90 * deg_to_rad} 0 0"/>
|
||||
<axis xyz="0 0 1"/>
|
||||
</joint>
|
||||
|
||||
<transmission name="${name}_steer_joint_trans">
|
||||
<type>transmission_interface/SimpleTransmission</type>
|
||||
<actuator name="${name}_steer_joint_motor">
|
||||
<mechanicalReduction>1</mechanicalReduction>
|
||||
<hardwareInterface>hardware_interface/PositionJointInterface</hardwareInterface>
|
||||
</actuator>
|
||||
<joint name="${name}_steer_joint">
|
||||
<hardwareInterface>hardware_interface/PositionJointInterface</hardwareInterface>
|
||||
</joint>
|
||||
</transmission>
|
||||
|
||||
<transmission name="${name}_wheel_joint_trans">
|
||||
<type>transmission_interface/SimpleTransmission</type>
|
||||
<actuator name="${name}_wheel_joint_motor">
|
||||
<mechanicalReduction>1</mechanicalReduction>
|
||||
<hardwareInterface>hardware_interface/VelocityJointInterface</hardwareInterface>
|
||||
</actuator>
|
||||
<joint name="${name}_wheel_joint">
|
||||
<hardwareInterface>hardware_interface/VelocityJointInterface</hardwareInterface>
|
||||
</joint>
|
||||
</transmission>
|
||||
|
||||
<gazebo reference="${name}_steer_link">
|
||||
<material>Gazebo/Blue</material>
|
||||
</gazebo>
|
||||
|
||||
<gazebo reference="${name}_wheel_link">
|
||||
<material>Gazebo/Red</material>
|
||||
</gazebo>
|
||||
</xacro:macro>
|
||||
|
||||
<!-- Bicycle model rear wheel link (required for steer_drive_controller) -->
|
||||
<xacro:macro name="rear_wheel"
|
||||
params="
|
||||
name
|
||||
parent
|
||||
wheel_radius
|
||||
wheel_thickness
|
||||
wheel_mass
|
||||
*origin">
|
||||
<link name="${name}_wheel_link">
|
||||
<visual>
|
||||
<origin xyz="0 0 0" rpy="0 0 0"/>
|
||||
<geometry>
|
||||
<cylinder radius="${wheel_radius}" length="${wheel_thickness}"/>
|
||||
</geometry>
|
||||
<material name="yellow" />
|
||||
</visual>
|
||||
<collision>
|
||||
<origin xyz="0 0 0" rpy="0 0 0"/>
|
||||
<geometry>
|
||||
<cylinder radius="${wheel_radius}" length="${wheel_thickness}"/>
|
||||
</geometry>
|
||||
</collision>
|
||||
<xacro:solid_cylinder_inertial
|
||||
rpy="0 0 0" xyz="0 0 0"
|
||||
mass="${wheel_mass}"
|
||||
radius="${wheel_radius}" length="${wheel_thickness}" />
|
||||
</link>
|
||||
|
||||
<joint name="${name}_wheel_joint" type="continuous">
|
||||
<parent link="${parent}_link"/>
|
||||
<child link="${name}_wheel_link"/>
|
||||
<xacro:insert_block name="origin"/>
|
||||
<axis xyz="0 0 1"/>
|
||||
</joint>
|
||||
|
||||
<transmission name="${name}_wheel_joint_trans">
|
||||
<type>transmission_interface/SimpleTransmission</type>
|
||||
<actuator name="${name}_wheel_joint_motor">
|
||||
<mechanicalReduction>1</mechanicalReduction>
|
||||
<hardwareInterface>hardware_interface/VelocityJointInterface</hardwareInterface>
|
||||
</actuator>
|
||||
<joint name="${name}_wheel_joint">
|
||||
<hardwareInterface>hardware_interface/VelocityJointInterface</hardwareInterface>
|
||||
</joint>
|
||||
</transmission>
|
||||
|
||||
<gazebo reference="${name}_wheel_link">
|
||||
<material>Gazebo/Yellow</material>
|
||||
</gazebo>
|
||||
</xacro:macro>
|
||||
|
||||
<!-- Bicycle model front wheel link (passive - no transmission) -->
|
||||
<xacro:macro name="front_wheel"
|
||||
params="
|
||||
name
|
||||
parent
|
||||
wheel_radius
|
||||
wheel_thickness
|
||||
wheel_mass
|
||||
*origin">
|
||||
<link name="${name}_wheel_link">
|
||||
<visual>
|
||||
<origin xyz="0 0 0" rpy="0 0 0"/>
|
||||
<geometry>
|
||||
<cylinder radius="${wheel_radius}" length="${wheel_thickness}"/>
|
||||
</geometry>
|
||||
<material name="yellow" />
|
||||
</visual>
|
||||
<collision>
|
||||
<origin xyz="0 0 0" rpy="0 0 0"/>
|
||||
<geometry>
|
||||
<cylinder radius="${wheel_radius}" length="${wheel_thickness}"/>
|
||||
</geometry>
|
||||
</collision>
|
||||
<xacro:solid_cylinder_inertial
|
||||
rpy="0 0 0" xyz="0 0 0"
|
||||
mass="${wheel_mass}"
|
||||
radius="${wheel_radius}" length="${wheel_thickness}" />
|
||||
</link>
|
||||
|
||||
<joint name="${name}_wheel_joint" type="continuous">
|
||||
<parent link="${parent}_link"/>
|
||||
<child link="${name}_wheel_link"/>
|
||||
<xacro:insert_block name="origin"/>
|
||||
<axis xyz="0 0 1"/>
|
||||
</joint>
|
||||
|
||||
<gazebo reference="${name}_wheel_link">
|
||||
<material>Gazebo/Yellow</material>
|
||||
</gazebo>
|
||||
|
||||
<gazebo reference="${name}_wheel_joint">
|
||||
<provideFeedback>true</provideFeedback>
|
||||
</gazebo>
|
||||
</xacro:macro>
|
||||
|
||||
<!-- Car steering model rear wheel links (left/right) -->
|
||||
<xacro:macro name="rear_wheel_lr"
|
||||
params="
|
||||
name
|
||||
parent
|
||||
reflect
|
||||
wheel_radius
|
||||
wheel_thickness
|
||||
wheel_mass
|
||||
*origin">
|
||||
<link name="${name}_wheel_link">
|
||||
<collision>
|
||||
<origin xyz="0 0 0" rpy="0 0 0"/>
|
||||
<geometry>
|
||||
<cylinder radius="${wheel_radius}" length="${wheel_thickness}"/>
|
||||
</geometry>
|
||||
</collision>
|
||||
<visual>
|
||||
<origin xyz="0 0 0" rpy="${-pi/2} ${(reflect * pi/2) + pi/2} 0"/>
|
||||
<geometry>
|
||||
<mesh filename="file://$(find dcaiti_control)/description/assets/ft24_wheel_simplified.dae" />
|
||||
</geometry>
|
||||
<material name="silver" />
|
||||
</visual>
|
||||
<xacro:solid_cylinder_inertial
|
||||
rpy="0 0 0" xyz="0 0 0"
|
||||
mass="${wheel_mass}"
|
||||
radius="${wheel_radius}" length="${wheel_thickness}" />
|
||||
</link>
|
||||
|
||||
<joint name="${name}_wheel_joint" type="continuous">
|
||||
<parent link="${parent}_link"/>
|
||||
<child link="${name}_wheel_link"/>
|
||||
<xacro:insert_block name="origin"/>
|
||||
<axis xyz="0 0 1"/>
|
||||
</joint>
|
||||
|
||||
<transmission name="${name}_wheel_joint_trans">
|
||||
<type>transmission_interface/SimpleTransmission</type>
|
||||
<actuator name="${name}_wheel_joint_motor">
|
||||
<mechanicalReduction>1</mechanicalReduction>
|
||||
<hardwareInterface>hardware_interface/VelocityJointInterface</hardwareInterface>
|
||||
</actuator>
|
||||
<joint name="${name}_wheel_joint">
|
||||
<hardwareInterface>hardware_interface/VelocityJointInterface</hardwareInterface>
|
||||
</joint>
|
||||
</transmission>
|
||||
|
||||
<gazebo reference="${name}_wheel_link">
|
||||
<material>Gazebo/Red</material>
|
||||
</gazebo>
|
||||
</xacro:macro>
|
||||
</robot>
|
@ -2,7 +2,9 @@ import os
|
||||
|
||||
from ament_index_python.packages import get_package_share_directory
|
||||
|
||||
from launch.substitutions import Command
|
||||
|
||||
from launch.actions import IncludeLaunchDescription, TimerAction
|
||||
from launch import LaunchDescription
|
||||
from launch.actions import IncludeLaunchDescription
|
||||
from launch.launch_description_sources import PythonLaunchDescriptionSource
|
||||
@ -18,14 +20,12 @@ from launch.event_handlers import OnProcessExit
|
||||
|
||||
def generate_launch_description():
|
||||
|
||||
|
||||
# Include the robot_state_publisher launch file, provided by our own package. Force sim time to be enabled
|
||||
# !!! MAKE SURE YOU SET THE PACKAGE NAME CORRECTLY !!!
|
||||
|
||||
package_name='dcaiti_control' #<--- CHANGE ME
|
||||
|
||||
use_ros2_control = LaunchConfiguration('use_ros2_control')
|
||||
world_path='worlds/willowgarage.world'
|
||||
|
||||
rsp = IncludeLaunchDescription(
|
||||
PythonLaunchDescriptionSource([os.path.join(
|
||||
@ -33,29 +33,43 @@ def generate_launch_description():
|
||||
)]), launch_arguments={'use_sim_time': 'true', 'use_ros2_control': use_ros2_control}.items()
|
||||
)
|
||||
gazebo_params_path = os.path.join(get_package_share_directory(package_name),'config','gazebo_config.yml')
|
||||
world_path = os.path.join(get_package_share_directory(package_name),'worlds')
|
||||
# Include the Gazebo launch file, provided by the gazebo_ros package
|
||||
|
||||
|
||||
gazebo = IncludeLaunchDescription(
|
||||
PythonLaunchDescriptionSource([os.path.join(
|
||||
get_package_share_directory('gazebo_ros'), 'launch', 'gazebo.launch.py')]),
|
||||
launch_arguments={'params_file': gazebo_params_path, 'world': world_path }.items()
|
||||
get_package_share_directory('ros_gz_sim'), 'launch', 'gz_sim.launch.py')]),
|
||||
launch_arguments=[('gz_args', [f" -r -v 1 {world_path}/empty.sdf"])],
|
||||
)
|
||||
|
||||
# Run the spawner node from the gazebo_ros package. The entity name doesn't really matter if you only have a single robot.
|
||||
spawn_entity = Node(package='gazebo_ros', executable='spawn_entity.py',
|
||||
spawn_entity = Node(package='ros_gz_sim', executable='create',
|
||||
arguments=[
|
||||
'-topic', 'robot_description',
|
||||
'-entity', 'dcaiti_control',
|
||||
'-z', '0.2',
|
||||
'-name', 'spawn_robot',
|
||||
'-z', '0.5',
|
||||
],
|
||||
output='screen'
|
||||
)
|
||||
|
||||
# Bridge
|
||||
bridge = Node(
|
||||
package='ros_gz_bridge',
|
||||
executable='parameter_bridge',
|
||||
arguments=[
|
||||
'/clock@rosgraph_msgs/msg/Clock[ignition.msgs.Clock',
|
||||
'/boxes_image@sensor_msgs/msg/Image@ignition.msgs.Image',
|
||||
'/camera_info@sensor_msgs/msg/CameraInfo@ignition.msgs.CameraInfo',
|
||||
'/lidar@sensor_msgs/msg/LaserScan@ignition.msgs.LaserScan',
|
||||
'/lidar/points@sensor_msgs/msg/PointCloud2@ignition.msgs.PointCloudPacked'
|
||||
],
|
||||
output='screen'
|
||||
)
|
||||
|
||||
diff_drive_spawner = Node(
|
||||
package="controller_manager",
|
||||
executable="spawner",
|
||||
arguments=["diff_cont"],
|
||||
arguments=["ackermann_steering_controller"],
|
||||
)
|
||||
|
||||
joint_broad_spawner = Node(
|
||||
@ -85,9 +99,10 @@ def generate_launch_description():
|
||||
'use_ros2_control',
|
||||
default_value='true',
|
||||
description='Use ros2_control if true'),
|
||||
bridge,
|
||||
rsp,
|
||||
gazebo,
|
||||
spawn_entity,
|
||||
delayed_diff_drive_spawner,
|
||||
delayed_joint_broad_spawner
|
||||
delayed_joint_broad_spawner,
|
||||
])
|
||||
|
134
src/dcaiti_control/worlds/empty.sdf
Normal file
@ -0,0 +1,134 @@
|
||||
<?xml version="1.0" ?>
|
||||
<!--
|
||||
Try inserting a model:
|
||||
|
||||
gz service -s /world/empty/create \
|
||||
--reqtype gz.msgs.EntityFactory \
|
||||
--reptype gz.msgs.Boolean \
|
||||
--timeout 300 \
|
||||
--req 'sdf: '\
|
||||
'"<?xml version=\"1.0\" ?>'\
|
||||
'<sdf version=\"1.6\">'\
|
||||
'<model name=\"spawned_model\">'\
|
||||
'<link name=\"link\">'\
|
||||
'<visual name=\"visual\">'\
|
||||
'<geometry><sphere><radius>1.0</radius></sphere></geometry>'\
|
||||
'</visual>'\
|
||||
'<collision name=\"visual\">'\
|
||||
'<geometry><sphere><radius>1.0</radius></sphere></geometry>'\
|
||||
'</collision>'\
|
||||
'</link>'\
|
||||
'</model>'\
|
||||
'</sdf>" '\
|
||||
'pose: {position: {z: 10}} '\
|
||||
'name: "new_name" '\
|
||||
'allow_renaming: true'
|
||||
|
||||
Then try deleting it:
|
||||
|
||||
gz service -s /world/empty/remove \
|
||||
--reqtype gz.msgs.Entity \
|
||||
--reptype gz.msgs.Boolean \
|
||||
--timeout 300 \
|
||||
--req 'name: "new_name" type: MODEL'
|
||||
|
||||
Try inserting a light:
|
||||
|
||||
gz service -s /world/empty/create --reqtype gz.msgs.EntityFactory --reptype gz.msgs.Boolean --timeout 300 --req 'sdf: '\
|
||||
'"<?xml version=\"1.0\" ?>'\
|
||||
'<sdf version=\"1.6\">'\
|
||||
'<light name=\"spawned_light\" type=\"directional\">'\
|
||||
'<pose>0 0 10 0.1 1.0 0</pose>'\
|
||||
'</light>'\
|
||||
'</sdf>"'
|
||||
|
||||
Then try deleting it:
|
||||
|
||||
gz service -s /world/empty/remove \
|
||||
--reqtype gz.msgs.Entity \
|
||||
--reptype gz.msgs.Boolean \
|
||||
--timeout 300 \
|
||||
--req 'name: "spawned_light" type: LIGHT'
|
||||
|
||||
Insert a light using a message and allow_renaming:
|
||||
|
||||
gz service -s /world/empty/create \
|
||||
--reqtype gz.msgs.EntityFactory \
|
||||
--reptype gz.msgs.Boolean \
|
||||
--timeout 300 \
|
||||
--req 'allow_renaming: true, light: {name: "spawned_light", type: 2, diffuse: {r: 1}}'
|
||||
|
||||
-->
|
||||
<sdf version="1.6">
|
||||
<world name="empty">
|
||||
<physics name="1ms" type="ignored">
|
||||
<max_step_size>0.001</max_step_size>
|
||||
<real_time_factor>1.0</real_time_factor>
|
||||
</physics>
|
||||
<plugin
|
||||
filename="ignition-gazebo-physics-system"
|
||||
name="gz::sim::systems::Physics">
|
||||
</plugin>
|
||||
<plugin
|
||||
filename="ignition-gazebo-user-commands-system"
|
||||
name="gz::sim::systems::UserCommands">
|
||||
</plugin>
|
||||
<plugin
|
||||
filename="ignition-gazebo-scene-broadcaster-system"
|
||||
name="gz::sim::systems::SceneBroadcaster">
|
||||
</plugin>
|
||||
<plugin
|
||||
filename="ignition-gazebo-contact-system"
|
||||
name="gz::sim::systems::Contact">
|
||||
</plugin>
|
||||
<plugin filename="libignition-gazebo-sensors-system.so" name="ignition::gazebo::systems::Sensors">
|
||||
<render_engine>ogre2</render_engine>
|
||||
</plugin>
|
||||
<scene>
|
||||
<shadows>false</shadows>
|
||||
<grid>false</grid>
|
||||
<origin_visual>false</origin_visual>
|
||||
</scene>
|
||||
|
||||
<light type="directional" name="sun">
|
||||
<pose>0 0 10 0 0 0</pose>
|
||||
<diffuse>0.8 0.8 0.8 1</diffuse>
|
||||
<specular>0.2 0.2 0.2 1</specular>
|
||||
<attenuation>
|
||||
<range>1000</range>
|
||||
<constant>0.9</constant>
|
||||
<linear>0.01</linear>
|
||||
<quadratic>0.001</quadratic>
|
||||
</attenuation>
|
||||
<direction>-0.5 0.1 -0.9</direction>
|
||||
</light>
|
||||
|
||||
<model name="ground_plane">
|
||||
<static>true</static>
|
||||
<link name="link">
|
||||
<collision name="collision">
|
||||
<geometry>
|
||||
<plane>
|
||||
<normal>0 0 1</normal>
|
||||
<size>100 100</size>
|
||||
</plane>
|
||||
</geometry>
|
||||
</collision>
|
||||
<visual name="visual">
|
||||
<geometry>
|
||||
<plane>
|
||||
<normal>0 0 1</normal>
|
||||
<size>100 100</size>
|
||||
</plane>
|
||||
</geometry>
|
||||
<material>
|
||||
<ambient>0.8 0.8 0.8 1</ambient>
|
||||
<diffuse>0.8 0.8 0.8 1</diffuse>
|
||||
<specular>0.8 0.8 0.8 1</specular>
|
||||
</material>
|
||||
</visual>
|
||||
</link>
|
||||
</model>
|
||||
|
||||
</world>
|
||||
</sdf>
|
39
src/dcaiti_control/worlds/labeled_cone.sdf
Normal file
@ -0,0 +1,39 @@
|
||||
<model name="box">
|
||||
<pose>0 -1 0.5 0 0 0</pose>
|
||||
<link name="box_link">
|
||||
<inertial>
|
||||
<inertia>
|
||||
<ixx>1</ixx>
|
||||
<ixy>0</ixy>
|
||||
<ixz>0</ixz>
|
||||
<iyy>1</iyy>
|
||||
<iyz>0</iyz>
|
||||
<izz>1</izz>
|
||||
</inertia>
|
||||
<mass>1.0</mass>
|
||||
</inertial>
|
||||
<collision name="box_collision">
|
||||
<geometry>
|
||||
<box>
|
||||
<size>1 1 1</size>
|
||||
</box>
|
||||
</geometry>
|
||||
</collision>
|
||||
|
||||
<visual name="box_visual">
|
||||
<geometry>
|
||||
<box>
|
||||
<size>1 1 1</size>
|
||||
</box>
|
||||
</geometry>
|
||||
<material>
|
||||
<ambient>0 0 0.5 1</ambient>
|
||||
<diffuse>0 0 1 1</diffuse>
|
||||
<specular>0 0 0.3 1</specular>
|
||||
</material>
|
||||
<plugin filename="ignition-gazebo-label-system" name="ignition::gazebo::systems::Label">
|
||||
<label>10</label>
|
||||
</plugin>
|
||||
</visual>
|
||||
</link>
|
||||
</model>
|
@ -1,31 +0,0 @@
|
||||
cmake_minimum_required(VERSION 3.8)
|
||||
project(dcaiti_navigation)
|
||||
|
||||
if(CMAKE_COMPILER_IS_GNUCXX OR CMAKE_CXX_COMPILER_ID MATCHES "Clang")
|
||||
add_compile_options(-Wall -Wextra -Wpedantic)
|
||||
endif()
|
||||
|
||||
# find dependencies
|
||||
find_package(ament_cmake REQUIRED)
|
||||
# uncomment the following section in order to fill in
|
||||
# further dependencies manually.
|
||||
# find_package(<dependency> REQUIRED)
|
||||
|
||||
if(BUILD_TESTING)
|
||||
find_package(ament_lint_auto REQUIRED)
|
||||
# the following line skips the linter which checks for copyrights
|
||||
# comment the line when a copyright and license is added to all source files
|
||||
set(ament_cmake_copyright_FOUND TRUE)
|
||||
# the following line skips cpplint (only works in a git repo)
|
||||
# comment the line when this package is in a git repo and when
|
||||
# a copyright and license is added to all source files
|
||||
set(ament_cmake_cpplint_FOUND TRUE)
|
||||
ament_lint_auto_find_test_dependencies()
|
||||
endif()
|
||||
|
||||
install(
|
||||
DIRECTORY config params launch worlds
|
||||
DESTINATION share/${PROJECT_NAME}
|
||||
)
|
||||
|
||||
ament_package()
|
@ -1,233 +0,0 @@
|
||||
### ekf config file ###
|
||||
ekf_filter_node:
|
||||
ros__parameters:
|
||||
|
||||
# The frequency, in Hz, at which the filter will output a position estimate. Note that the filter will not begin
|
||||
# computation until it receives at least one message from one of the inputs. It will then run continuously at the
|
||||
# frequency specified here, regardless of whether it receives more measurements. Defaults to 30 if unspecified.
|
||||
frequency: 30.0
|
||||
|
||||
# The period, in seconds, after which we consider a sensor to have timed out. In this event, we carry out a predict
|
||||
# cycle on the EKF without correcting it. This parameter can be thought of as the minimum frequency with which the
|
||||
# filter will generate new output. Defaults to 1 / frequency if not specified.
|
||||
sensor_timeout: 0.1
|
||||
|
||||
# ekf_localization_node and ukf_localization_node both use a 3D omnidirectional motion model. If this parameter is
|
||||
# set to true, no 3D information will be used in your state estimate. Use this if you are operating in a planar
|
||||
# environment and want to ignore the effect of small variations in the ground plane that might otherwise be detected
|
||||
# by, for example, an IMU. Defaults to false if unspecified.
|
||||
two_d_mode: true
|
||||
|
||||
# Use this parameter to provide an offset to the transform generated by ekf_localization_node. This can be used for
|
||||
# future dating the transform, which is required for interaction with some other packages. Defaults to 0.0 if
|
||||
# unspecified.
|
||||
transform_time_offset: 0.0
|
||||
|
||||
# Use this parameter to provide specify how long the tf listener should wait for a transform to become available.
|
||||
# Defaults to 0.0 if unspecified.
|
||||
transform_timeout: 0.0
|
||||
|
||||
# If you're having trouble, try setting this to true, and then echo the /diagnostics_agg topic to see if the node is
|
||||
# unhappy with any settings or data.
|
||||
print_diagnostics: true
|
||||
|
||||
# Debug settings. Not for the faint of heart. Outputs a ludicrous amount of information to the file specified by
|
||||
# debug_out_file. I hope you like matrices! Please note that setting this to true will have strongly deleterious
|
||||
# effects on the performance of the node. Defaults to false if unspecified.
|
||||
debug: false
|
||||
|
||||
# Defaults to "robot_localization_debug.txt" if unspecified. Please specify the full path.
|
||||
debug_out_file: /home/focalfossa/dev_ws/src/basic_mobile_robot/debug_ekf.txt
|
||||
|
||||
# Whether we'll allow old measurements to cause a re-publication of the updated state
|
||||
permit_corrected_publication: false
|
||||
|
||||
# Whether to publish the acceleration state. Defaults to false if unspecified.
|
||||
publish_acceleration: false
|
||||
|
||||
# Whether to broadcast the transformation over the /tf topic. Defaults to true if unspecified.
|
||||
publish_tf: true
|
||||
|
||||
# REP-105 (http://www.ros.org/reps/rep-0105.html) specifies four principal coordinate frames: base_link, odom, map, and
|
||||
# earth. base_link is the coordinate frame that is affixed to the robot. Both odom and map are world-fixed frames.
|
||||
# The robot's position in the odom frame will drift over time, but is accurate in the short term and should be
|
||||
# continuous. The odom frame is therefore the best frame for executing local motion plans. The map frame, like the odom
|
||||
# frame, is a world-fixed coordinate frame, and while it contains the most globally accurate position estimate for your
|
||||
# robot, it is subject to discrete jumps, e.g., due to the fusion of GPS data or a correction from a map-based
|
||||
# localization node. The earth frame is used to relate multiple map frames by giving them a common reference frame.
|
||||
# ekf_localization_node and ukf_localization_node are not concerned with the earth frame.
|
||||
# Here is how to use the following settings:
|
||||
# 1. Set the map_frame, odom_frame, and base_link frames to the appropriate frame names for your system.
|
||||
# 1a. If your system does not have a map_frame, just remove it, and make sure "world_frame" is set to the value of
|
||||
# odom_frame.
|
||||
# 2. If you are fusing continuous position data such as wheel encoder odometry, visual odometry, or IMU data, set
|
||||
# "world_frame" to your odom_frame value. This is the default behavior for robot_localization's state estimation nodes.
|
||||
# 3. If you are fusing global absolute position data that is subject to discrete jumps (e.g., GPS or position updates
|
||||
# from landmark observations) then:
|
||||
# 3a. Set your "world_frame" to your map_frame value
|
||||
# 3b. MAKE SURE something else is generating the odom->base_link transform. Note that this can even be another state
|
||||
# estimation node from robot_localization! However, that instance should *not* fuse the global data.
|
||||
map_frame: map # Defaults to "map" if unspecified
|
||||
odom_frame: odom # Defaults to "odom" if unspecified
|
||||
base_link_frame: base_footprint # Defaults to "base_link" if unspecified
|
||||
world_frame: odom # Defaults to the value of odom_frame if unspecified
|
||||
|
||||
# The filter accepts an arbitrary number of inputs from each input message type (nav_msgs/Odometry,
|
||||
# geometry_msgs/PoseWithCovarianceStamped, geometry_msgs/TwistWithCovarianceStamped,
|
||||
# sensor_msgs/Imu). To add an input, simply append the next number in the sequence to its "base" name, e.g., odom0,
|
||||
# odom1, twist0, twist1, imu0, imu1, imu2, etc. The value should be the topic name. These parameters obviously have no
|
||||
# default values, and must be specified.
|
||||
odom0: wheel/odometry
|
||||
|
||||
# Each sensor reading updates some or all of the filter's state. These options give you greater control over which
|
||||
# values from each measurement are fed to the filter. For example, if you have an odometry message as input, but only
|
||||
# want to use its Z position value, then set the entire vector to false, except for the third entry. The order of the
|
||||
# values is x, y, z, roll, pitch, yaw, vx, vy, vz, vroll, vpitch, vyaw, ax, ay, az. Note that not some message types
|
||||
# do not provide some of the state variables estimated by the filter. For example, a TwistWithCovarianceStamped message
|
||||
# has no pose information, so the first six values would be meaningless in that case. Each vector defaults to all false
|
||||
# if unspecified, effectively making this parameter required for each sensor.
|
||||
odom0_config: [true, true, true,
|
||||
false, false, false,
|
||||
true, true, true,
|
||||
false, false, true,
|
||||
false, false, false]
|
||||
|
||||
# [x_pos , y_pos , z_pos,
|
||||
# roll , pitch , yaw,
|
||||
# x_vel , y_vel , z_vel,
|
||||
# roll_vel, pitch_vel, yaw_vel,
|
||||
# x_accel , y_accel , z_accel]
|
||||
|
||||
# If you have high-frequency data or are running with a low frequency parameter value, then you may want to increase
|
||||
# the size of the subscription queue so that more measurements are fused.
|
||||
odom0_queue_size: 2
|
||||
|
||||
# [ADVANCED] Large messages in ROS can exhibit strange behavior when they arrive at a high frequency. This is a result
|
||||
# of Nagle's algorithm. This option tells the ROS subscriber to use the tcpNoDelay option, which disables Nagle's
|
||||
# algorithm.
|
||||
odom0_nodelay: false
|
||||
|
||||
# [ADVANCED] When measuring one pose variable with two sensors, a situation can arise in which both sensors under-
|
||||
# report their covariances. This can lead to the filter rapidly jumping back and forth between each measurement as they
|
||||
# arrive. In these cases, it often makes sense to (a) correct the measurement covariances, or (b) if velocity is also
|
||||
# measured by one of the sensors, let one sensor measure pose, and the other velocity. However, doing (a) or (b) isn't
|
||||
# always feasible, and so we expose the differential parameter. When differential mode is enabled, all absolute pose
|
||||
# data is converted to velocity data by differentiating the absolute pose measurements. These velocities are then
|
||||
# integrated as usual. NOTE: this only applies to sensors that provide pose measurements; setting differential to true
|
||||
# for twist measurements has no effect.
|
||||
odom0_differential: false
|
||||
|
||||
# [ADVANCED] When the node starts, if this parameter is true, then the first measurement is treated as a "zero point"
|
||||
# for all future measurements. While you can achieve the same effect with the differential paremeter, the key
|
||||
# difference is that the relative parameter doesn't cause the measurement to be converted to a velocity before
|
||||
# integrating it. If you simply want your measurements to start at 0 for a given sensor, set this to true.
|
||||
odom0_relative: false
|
||||
|
||||
# [ADVANCED] If your data is subject to outliers, use these threshold settings, expressed as Mahalanobis distances, to
|
||||
# control how far away from the current vehicle state a sensor measurement is permitted to be. Each defaults to
|
||||
# numeric_limits<double>::max() if unspecified. It is strongly recommended that these parameters be removed if not
|
||||
# required. Data is specified at the level of pose and twist variables, rather than for each variable in isolation.
|
||||
# For messages that have both pose and twist data, the parameter specifies to which part of the message we are applying
|
||||
# the thresholds.
|
||||
odom0_pose_rejection_threshold: 5.0
|
||||
odom0_twist_rejection_threshold: 1.0
|
||||
|
||||
imu0: imu/data
|
||||
imu0_config: [false, false, false,
|
||||
true, true, true,
|
||||
false, false, false,
|
||||
true, true, true,
|
||||
true, true, true]
|
||||
|
||||
# [x_pos , y_pos , z_pos,
|
||||
# roll , pitch , yaw,
|
||||
# x_vel , y_vel , z_vel,
|
||||
# roll_vel, pitch_vel, yaw_vel,
|
||||
# x_accel , y_accel , z_accel]
|
||||
|
||||
imu0_nodelay: false
|
||||
imu0_differential: false
|
||||
imu0_relative: true
|
||||
imu0_queue_size: 5
|
||||
imu0_pose_rejection_threshold: 0.8 # Note the difference in parameter names
|
||||
imu0_twist_rejection_threshold: 0.8 #
|
||||
imu0_linear_acceleration_rejection_threshold: 0.8 #
|
||||
|
||||
# [ADVANCED] Some IMUs automatically remove acceleration due to gravity, and others don't. If yours doesn't, please set
|
||||
# this to true, and *make sure* your data conforms to REP-103, specifically, that the data is in ENU frame.
|
||||
imu0_remove_gravitational_acceleration: true
|
||||
|
||||
# [ADVANCED] The EKF and UKF models follow a standard predict/correct cycle. During prediction, if there is no
|
||||
# acceleration reference, the velocity at time t+1 is simply predicted to be the same as the velocity at time t. During
|
||||
# correction, this predicted value is fused with the measured value to produce the new velocity estimate. This can be
|
||||
# problematic, as the final velocity will effectively be a weighted average of the old velocity and the new one. When
|
||||
# this velocity is the integrated into a new pose, the result can be sluggish covergence. This effect is especially
|
||||
# noticeable with LIDAR data during rotations. To get around it, users can try inflating the process_noise_covariance
|
||||
# for the velocity variable in question, or decrease the variance of the variable in question in the measurement
|
||||
# itself. In addition, users can also take advantage of the control command being issued to the robot at the time we
|
||||
# make the prediction. If control is used, it will get converted into an acceleration term, which will be used during
|
||||
# predicition. Note that if an acceleration measurement for the variable in question is available from one of the
|
||||
# inputs, the control term will be ignored.
|
||||
# Whether or not we use the control input during predicition. Defaults to false.
|
||||
use_control: false
|
||||
# Whether the input (assumed to be cmd_vel) is a geometry_msgs/Twist or geometry_msgs/TwistStamped message. Defaults to
|
||||
# false.
|
||||
stamped_control: false
|
||||
# The last issued control command will be used in prediction for this period. Defaults to 0.2.
|
||||
control_timeout: 0.2
|
||||
# Which velocities are being controlled. Order is vx, vy, vz, vroll, vpitch, vyaw.
|
||||
control_config: [true, false, false, false, false, true]
|
||||
# Places limits on how large the acceleration term will be. Should match your robot's kinematics.
|
||||
acceleration_limits: [1.3, 0.0, 0.0, 0.0, 0.0, 3.4]
|
||||
# Acceleration and deceleration limits are not always the same for robots.
|
||||
deceleration_limits: [1.3, 0.0, 0.0, 0.0, 0.0, 4.5]
|
||||
# If your robot cannot instantaneously reach its acceleration limit, the permitted change can be controlled with these
|
||||
# gains
|
||||
acceleration_gains: [0.8, 0.0, 0.0, 0.0, 0.0, 0.9]
|
||||
# If your robot cannot instantaneously reach its deceleration limit, the permitted change can be controlled with these
|
||||
# gains
|
||||
deceleration_gains: [1.0, 0.0, 0.0, 0.0, 0.0, 1.0]
|
||||
# [ADVANCED] The process noise covariance matrix can be difficult to tune, and can vary for each application, so it is
|
||||
# exposed as a configuration parameter. This matrix represents the noise we add to the total error after each
|
||||
# prediction step. The better the omnidirectional motion model matches your system, the smaller these values can be.
|
||||
# However, if users find that a given variable is slow to converge, one approach is to increase the
|
||||
# process_noise_covariance diagonal value for the variable in question, which will cause the filter's predicted error
|
||||
# to be larger, which will cause the filter to trust the incoming measurement more during correction. The values are
|
||||
# ordered as x, y, z, roll, pitch, yaw, vx, vy, vz, vroll, vpitch, vyaw, ax, ay, az. Defaults to the matrix below if
|
||||
# unspecified.
|
||||
process_noise_covariance: [0.05, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0,
|
||||
0.0, 0.05, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0,
|
||||
0.0, 0.0, 0.06, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0,
|
||||
0.0, 0.0, 0.0, 0.03, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0,
|
||||
0.0, 0.0, 0.0, 0.0, 0.03, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0,
|
||||
0.0, 0.0, 0.0, 0.0, 0.0, 0.06, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0,
|
||||
0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.025, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0,
|
||||
0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.025, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0,
|
||||
0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.04, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0,
|
||||
0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.01, 0.0, 0.0, 0.0, 0.0, 0.0,
|
||||
0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.01, 0.0, 0.0, 0.0, 0.0,
|
||||
0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.02, 0.0, 0.0, 0.0,
|
||||
0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.01, 0.0, 0.0,
|
||||
0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.01, 0.0,
|
||||
0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.015]
|
||||
# [ADVANCED] This represents the initial value for the state estimate error covariance matrix. Setting a diagonal
|
||||
# value (variance) to a large value will result in rapid convergence for initial measurements of the variable in
|
||||
# question. Users should take care not to use large values for variables that will not be measured directly. The values
|
||||
# are ordered as x, y, z, roll, pitch, yaw, vx, vy, vz, vroll, vpitch, vyaw, ax, ay, az. Defaults to the matrix below
|
||||
#if unspecified.
|
||||
initial_estimate_covariance: [1e-9, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0,
|
||||
0.0, 1e-9, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0,
|
||||
0.0, 0.0, 1e-9, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0,
|
||||
0.0, 0.0, 0.0, 1e-9, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0,
|
||||
0.0, 0.0, 0.0, 0.0, 1e-9, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0,
|
||||
0.0, 0.0, 0.0, 0.0, 0.0, 1e-9, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0,
|
||||
0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 1e-9, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0,
|
||||
0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 1e-9, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0,
|
||||
0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 1e-9, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0,
|
||||
0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 1e-9, 0.0, 0.0, 0.0, 0.0, 0.0,
|
||||
0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 1e-9, 0.0, 0.0, 0.0, 0.0,
|
||||
0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 1e-9, 0.0, 0.0, 0.0,
|
||||
0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 1e-9, 0.0, 0.0,
|
||||
0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 1e-9, 0.0,
|
||||
0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 1e-9]
|
||||
|
@ -1,11 +0,0 @@
|
||||
planner_server:
|
||||
ros__parameters:
|
||||
planner_plugins: ['GridBased']
|
||||
GridBased:
|
||||
plugin: 'nav2_navfn_planner/NavfnPlanner'
|
||||
|
||||
controller_server:
|
||||
ros__parameters:
|
||||
controller_plugins: ["FollowPath"]
|
||||
FollowPath:
|
||||
plugin: "dwb_core::DWBLocalPlanner"
|
@ -1,6 +0,0 @@
|
||||
slam_toolbox:
|
||||
ros__parameters:
|
||||
base_frame: base_link
|
||||
map_update_interval: 1.0
|
||||
scan_topic: /scan_no_nan
|
||||
odom_topic: /diff_cont/odom
|
@ -1,138 +0,0 @@
|
||||
# Author: Addison Sears-Collins
|
||||
# Date: September 2, 2021
|
||||
# Description: Launch a basic mobile robot using the ROS 2 Navigation Stack
|
||||
# https://automaticaddison.com
|
||||
|
||||
import os
|
||||
from pathlib import Path
|
||||
from ament_index_python import get_package_share_directory
|
||||
from launch import LaunchDescription
|
||||
from launch.actions import DeclareLaunchArgument, IncludeLaunchDescription, SetEnvironmentVariable
|
||||
from launch.launch_description_sources import PythonLaunchDescriptionSource
|
||||
from launch.substitutions import Command, LaunchConfiguration, PythonExpression
|
||||
from launch_ros.substitutions import FindPackageShare
|
||||
from launch_ros.actions import Node, SetRemap
|
||||
from launch.actions import GroupAction
|
||||
|
||||
def generate_launch_description():
|
||||
|
||||
# Set the path to different files and folders.
|
||||
pkg_share = get_package_share_directory('dcaiti_navigation')
|
||||
nav2_params_path = os.path.join(pkg_share, 'params', 'nav2_params.yaml')
|
||||
behavior_tree_xml_path = os.path.join(get_package_share_directory('nav2_bt_navigator'), 'behavior_trees', 'navigate_w_replanning_and_recovery.xml')
|
||||
|
||||
# Launch configuration variables specific to simulation
|
||||
autostart = LaunchConfiguration('autostart')
|
||||
default_bt_xml_filename = LaunchConfiguration('default_bt_xml_filename')
|
||||
map_yaml_file = LaunchConfiguration('map')
|
||||
namespace = LaunchConfiguration('namespace')
|
||||
params_file = LaunchConfiguration('params_file')
|
||||
slam = LaunchConfiguration('slam')
|
||||
use_namespace = LaunchConfiguration('use_namespace')
|
||||
use_sim_time = LaunchConfiguration('use_sim_time')
|
||||
|
||||
# Declare the launch arguments
|
||||
declare_namespace_cmd = DeclareLaunchArgument(
|
||||
name='namespace',
|
||||
default_value='',
|
||||
description='Top-level namespace')
|
||||
|
||||
declare_use_namespace_cmd = DeclareLaunchArgument(
|
||||
name='use_namespace',
|
||||
default_value='False',
|
||||
description='Whether to apply a namespace to the navigation stack')
|
||||
|
||||
declare_autostart_cmd = DeclareLaunchArgument(
|
||||
name='autostart',
|
||||
default_value='true',
|
||||
description='Automatically startup the nav2 stack')
|
||||
|
||||
declare_bt_xml_cmd = DeclareLaunchArgument(
|
||||
name='default_bt_xml_filename',
|
||||
default_value=behavior_tree_xml_path,
|
||||
description='Full path to the behavior tree xml file to use')
|
||||
|
||||
declare_params_file_cmd = DeclareLaunchArgument(
|
||||
name='params_file',
|
||||
default_value=nav2_params_path,
|
||||
description='Full path to the ROS2 parameters file to use for all launched nodes')
|
||||
|
||||
declare_use_sim_time_cmd = DeclareLaunchArgument(
|
||||
name='use_sim_time',
|
||||
default_value='False',
|
||||
description='Use simulation (Gazebo) clock if true')
|
||||
|
||||
slam_params = os.path.join(
|
||||
get_package_share_directory('dcaiti_navigation'), # <-- Replace with your package name
|
||||
'params',
|
||||
'nav2_params.yaml'
|
||||
)
|
||||
|
||||
|
||||
start_ros2_navigation_cmd = GroupAction(
|
||||
actions=[
|
||||
SetRemap(src='/cmd_vel',dst='/cmd_vel_nav'),
|
||||
IncludeLaunchDescription(
|
||||
PythonLaunchDescriptionSource([os.path.join(
|
||||
get_package_share_directory('nav2_bringup'),'launch','navigation_launch.py')]),
|
||||
launch_arguments={
|
||||
'use_sim_time': 'false',
|
||||
'-r': '/cmd_vel:=/cmd_vel_nav'
|
||||
}.items()
|
||||
)
|
||||
]
|
||||
)
|
||||
|
||||
|
||||
|
||||
slam_toolbox = IncludeLaunchDescription(
|
||||
PythonLaunchDescriptionSource([os.path.join(
|
||||
get_package_share_directory('slam_toolbox'),'launch','online_async_launch.py'
|
||||
)]),
|
||||
launch_arguments={
|
||||
'use_sim_time': 'false',
|
||||
'slam_params_file': slam_params}.items()
|
||||
)
|
||||
|
||||
|
||||
node_fix_lidar = Node(
|
||||
package="dcaitirobot",
|
||||
executable="fixlidar",
|
||||
name="fixlidar",
|
||||
)
|
||||
|
||||
tfs1 = Node(package = "tf2_ros",
|
||||
executable = "static_transform_publisher",
|
||||
arguments = ["0", "0", "0" ,"0", "0", "0", "base_link", "velodyne"])
|
||||
|
||||
tfs2 = Node(package = "tf2_ros",
|
||||
executable = "static_transform_publisher",
|
||||
arguments = ["0", "0", "0" ,"0", "0", "0", "base_link", "base_footprint"])
|
||||
|
||||
|
||||
|
||||
exploration = IncludeLaunchDescription(
|
||||
PythonLaunchDescriptionSource([os.path.join(
|
||||
get_package_share_directory('explore_lite'),'launch','explore.launch.py'
|
||||
)]),
|
||||
launch_arguments={
|
||||
'use_sim_time': 'false'}.items()
|
||||
)
|
||||
|
||||
# Create the launch description and populate
|
||||
ld = LaunchDescription([
|
||||
declare_namespace_cmd,
|
||||
declare_use_namespace_cmd,
|
||||
declare_autostart_cmd,
|
||||
declare_bt_xml_cmd,
|
||||
declare_params_file_cmd,
|
||||
declare_use_sim_time_cmd,
|
||||
start_ros2_navigation_cmd,
|
||||
slam_toolbox,
|
||||
node_fix_lidar,
|
||||
tfs1,
|
||||
tfs2,
|
||||
exploration,
|
||||
])
|
||||
|
||||
return ld
|
@ -1,7 +0,0 @@
|
||||
image: my_map.pgm
|
||||
mode: trinary
|
||||
resolution: 0.05
|
||||
origin: [-18.7, -17.5, 0]
|
||||
negate: 0
|
||||
occupied_thresh: 0.65
|
||||
free_thresh: 0.25
|
@ -1,6 +0,0 @@
|
||||
image: smalltown_world.pgm
|
||||
resolution: 0.050000
|
||||
origin: [-51.224998, -51.224998, 0.000000]
|
||||
negate: 0
|
||||
occupied_thresh: 0.65
|
||||
free_thresh: 0.196
|
@ -1,18 +0,0 @@
|
||||
<?xml version="1.0"?>
|
||||
<?xml-model href="http://download.ros.org/schema/package_format3.xsd" schematypens="http://www.w3.org/2001/XMLSchema"?>
|
||||
<package format="3">
|
||||
<name>dcaiti_navigation</name>
|
||||
<version>0.0.0</version>
|
||||
<description>TODO: Package description</description>
|
||||
<maintainer email="you@example.com">korjakow</maintainer>
|
||||
<license>TODO: License declaration</license>
|
||||
|
||||
<buildtool_depend>ament_cmake</buildtool_depend>
|
||||
|
||||
<test_depend>ament_lint_auto</test_depend>
|
||||
<test_depend>ament_lint_common</test_depend>
|
||||
|
||||
<export>
|
||||
<build_type>ament_cmake</build_type>
|
||||
</export>
|
||||
</package>
|
@ -1,401 +0,0 @@
|
||||
amcl:
|
||||
ros__parameters:
|
||||
use_sim_time: False
|
||||
alpha1: 0.002
|
||||
alpha2: 0.002
|
||||
alpha3: 0.002
|
||||
alpha4: 0.002
|
||||
alpha5: 0.002
|
||||
base_frame_id: "base_link"
|
||||
beam_skip_distance: 0.5
|
||||
beam_skip_error_threshold: 0.9
|
||||
beam_skip_threshold: 0.3
|
||||
do_beamskip: false
|
||||
global_frame_id: "map"
|
||||
initial_pose: [0.0, 0.0, 0.0, 0.0]
|
||||
lambda_short: 0.1
|
||||
laser_likelihood_max_dist: 2.0
|
||||
laser_max_range: 100.0
|
||||
laser_min_range: -1.0
|
||||
laser_model_type: "likelihood_field"
|
||||
max_beams: 60
|
||||
max_particles: 2000
|
||||
min_particles: 500
|
||||
odom_frame_id: "odom"
|
||||
pf_err: 0.05
|
||||
pf_z: 0.99
|
||||
recovery_alpha_fast: 0.0
|
||||
recovery_alpha_slow: 0.0
|
||||
resample_interval: 1
|
||||
robot_model_type: "differential"
|
||||
save_pose_rate: 0.5
|
||||
set_initial_pose: False
|
||||
sigma_hit: 0.2
|
||||
tf_broadcast: true
|
||||
transform_tolerance: 5.0
|
||||
update_min_a: 0.2
|
||||
update_min_d: 0.25
|
||||
z_hit: 0.5
|
||||
z_max: 0.05
|
||||
z_rand: 0.5
|
||||
z_short: 0.05
|
||||
scan_topic: scan
|
||||
|
||||
amcl_map_client:
|
||||
ros__parameters:
|
||||
use_sim_time: False
|
||||
|
||||
amcl_rclcpp_node:
|
||||
ros__parameters:
|
||||
use_sim_time: False
|
||||
|
||||
bt_navigator:
|
||||
ros__parameters:
|
||||
use_sim_time: False
|
||||
global_frame: map
|
||||
robot_base_frame: base_link
|
||||
odom_topic: /diff_cont/odom #/wheel/odometry
|
||||
bt_loop_duration: 10
|
||||
default_server_timeout: 20
|
||||
enable_groot_monitoring: True
|
||||
groot_zmq_publisher_port: 1666
|
||||
groot_zmq_server_port: 1667
|
||||
# 'default_nav_through_poses_bt_xml' and 'default_nav_to_pose_bt_xml' are use defaults:
|
||||
# nav2_bt_navigator/navigate_to_pose_w_replanning_and_recovery.xml
|
||||
# nav2_bt_navigator/navigate_through_poses_w_replanning_and_recovery.xml
|
||||
# They can be set here or via a RewrittenYaml remap from a parent launch file to Nav2.
|
||||
plugin_lib_names:
|
||||
- nav2_compute_path_to_pose_action_bt_node
|
||||
- nav2_compute_path_through_poses_action_bt_node
|
||||
- nav2_follow_path_action_bt_node
|
||||
- nav2_back_up_action_bt_node
|
||||
- nav2_spin_action_bt_node
|
||||
- nav2_wait_action_bt_node
|
||||
- nav2_clear_costmap_service_bt_node
|
||||
- nav2_is_stuck_condition_bt_node
|
||||
- nav2_goal_reached_condition_bt_node
|
||||
- nav2_goal_updated_condition_bt_node
|
||||
- nav2_initial_pose_received_condition_bt_node
|
||||
- nav2_reinitialize_global_localization_service_bt_node
|
||||
- nav2_rate_controller_bt_node
|
||||
- nav2_distance_controller_bt_node
|
||||
- nav2_speed_controller_bt_node
|
||||
- nav2_truncate_path_action_bt_node
|
||||
- nav2_goal_updater_node_bt_node
|
||||
- nav2_recovery_node_bt_node
|
||||
- nav2_pipeline_sequence_bt_node
|
||||
- nav2_round_robin_node_bt_node
|
||||
- nav2_transform_available_condition_bt_node
|
||||
- nav2_time_expired_condition_bt_node
|
||||
- nav2_distance_traveled_condition_bt_node
|
||||
- nav2_single_trigger_bt_node
|
||||
- nav2_is_battery_low_condition_bt_node
|
||||
- nav2_navigate_through_poses_action_bt_node
|
||||
- nav2_navigate_to_pose_action_bt_node
|
||||
- nav2_remove_passed_goals_action_bt_node
|
||||
- nav2_planner_selector_bt_node
|
||||
- nav2_controller_selector_bt_node
|
||||
- nav2_goal_checker_selector_bt_node
|
||||
|
||||
bt_navigator_rclcpp_node:
|
||||
ros__parameters:
|
||||
use_sim_time: False
|
||||
|
||||
controller_server:
|
||||
ros__parameters:
|
||||
use_sim_time: False
|
||||
controller_frequency: 2.0
|
||||
min_x_velocity_threshold: 0.001
|
||||
min_y_velocity_threshold: 0.5
|
||||
min_theta_velocity_threshold: 0.001
|
||||
failure_tolerance: 0.3
|
||||
progress_checker_plugin: "progress_checker"
|
||||
goal_checker_plugins: ["general_goal_checker"] # "precise_goal_checker"
|
||||
controller_plugins: ["FollowPath"]
|
||||
|
||||
# Progress checker parameters
|
||||
progress_checker:
|
||||
plugin: "nav2_controller::SimpleProgressChecker"
|
||||
required_movement_radius: 0.5
|
||||
movement_time_allowance: 10.0
|
||||
# Goal checker parameters
|
||||
#precise_goal_checker:
|
||||
# plugin: "nav2_controller::SimpleGoalChecker"
|
||||
# xy_goal_tolerance: 0.25
|
||||
# yaw_goal_tolerance: 0.25
|
||||
# stateful: True
|
||||
general_goal_checker:
|
||||
stateful: True
|
||||
plugin: "nav2_controller::SimpleGoalChecker"
|
||||
xy_goal_tolerance: 0.25
|
||||
yaw_goal_tolerance: 0.25
|
||||
# DWB parameters
|
||||
FollowPath:
|
||||
plugin: "dwb_core::DWBLocalPlanner"
|
||||
debug_trajectory_details: True
|
||||
min_vel_x: 0.0
|
||||
min_vel_y: 0.0
|
||||
max_vel_x: 0.26
|
||||
max_vel_y: 0.0
|
||||
max_vel_theta: 1.0
|
||||
min_speed_xy: 0.0
|
||||
max_speed_xy: 0.26
|
||||
min_speed_theta: 0.0
|
||||
# Add high threshold velocity for turtlebot 3 issue.
|
||||
# https://github.com/ROBOTIS-GIT/turtlebot3_simulations/issues/75
|
||||
acc_lim_x: 2.5
|
||||
acc_lim_y: 0.0
|
||||
acc_lim_theta: 3.2
|
||||
decel_lim_x: -2.5
|
||||
decel_lim_y: 0.0
|
||||
decel_lim_theta: -3.2
|
||||
vx_samples: 20
|
||||
vy_samples: 5
|
||||
vtheta_samples: 20
|
||||
sim_time: 1.7
|
||||
linear_granularity: 0.05
|
||||
angular_granularity: 0.025
|
||||
transform_tolerance: 5.0
|
||||
xy_goal_tolerance: 0.25
|
||||
trans_stopped_velocity: 0.25
|
||||
short_circuit_trajectory_evaluation: True
|
||||
stateful: True
|
||||
critics: ["RotateToGoal", "Oscillation", "BaseObstacle", "GoalAlign", "PathAlign", "PathDist", "GoalDist"]
|
||||
BaseObstacle.scale: 0.02
|
||||
PathAlign.scale: 32.0
|
||||
PathAlign.forward_point_distance: 0.1
|
||||
GoalAlign.scale: 24.0
|
||||
GoalAlign.forward_point_distance: 0.1
|
||||
PathDist.scale: 32.0
|
||||
GoalDist.scale: 24.0
|
||||
RotateToGoal.scale: 32.0
|
||||
RotateToGoal.slowing_factor: 5.0
|
||||
RotateToGoal.lookahead_time: -1.0
|
||||
|
||||
controller_server_rclcpp_node:
|
||||
ros__parameters:
|
||||
use_sim_time: False
|
||||
|
||||
local_costmap:
|
||||
local_costmap:
|
||||
ros__parameters:
|
||||
update_frequency: 5.0
|
||||
publish_frequency: 2.0
|
||||
global_frame: odom
|
||||
robot_base_frame: base_link
|
||||
use_sim_time: False
|
||||
rolling_window: true
|
||||
width: 10
|
||||
height: 10
|
||||
resolution: 0.05
|
||||
footprint: "[ [0.21, 0.195], [0.21, -0.195], [-0.21, -0.195], [-0.21, 0.195] ]"
|
||||
plugins: ["voxel_layer", "inflation_layer"]
|
||||
inflation_layer:
|
||||
plugin: "nav2_costmap_2d::InflationLayer"
|
||||
cost_scaling_factor: 3.0
|
||||
inflation_radius: 0.55
|
||||
voxel_layer:
|
||||
plugin: "nav2_costmap_2d::VoxelLayer"
|
||||
enabled: True
|
||||
publish_voxel_map: True
|
||||
origin_z: 0.0
|
||||
z_resolution: 0.05
|
||||
z_voxels: 16
|
||||
max_obstacle_height: 2.0
|
||||
mark_threshold: 0
|
||||
observation_sources: scan
|
||||
scan:
|
||||
topic: /scan_no_nan
|
||||
max_obstacle_height: 2.0
|
||||
clearing: True
|
||||
marking: True
|
||||
data_type: "LaserScan"
|
||||
raytrace_max_range: 10.0
|
||||
raytrace_min_range: 0.0
|
||||
obstacle_max_range: 9.5
|
||||
obstacle_min_range: 0.0
|
||||
static_layer:
|
||||
map_subscribe_transient_local: True
|
||||
always_send_full_costmap: True
|
||||
local_costmap_client:
|
||||
ros__parameters:
|
||||
use_sim_time: False
|
||||
local_costmap_rclcpp_node:
|
||||
ros__parameters:
|
||||
use_sim_time: False
|
||||
|
||||
global_costmap:
|
||||
global_costmap:
|
||||
ros__parameters:
|
||||
update_frequency: 1.0
|
||||
publish_frequency: 1.0
|
||||
global_frame: map
|
||||
robot_base_frame: base_link
|
||||
use_sim_time: False
|
||||
robot_radius: 0.21
|
||||
resolution: 0.05
|
||||
track_unknown_space: true
|
||||
plugins: ["static_layer", "obstacle_layer", "inflation_layer"]
|
||||
obstacle_layer:
|
||||
plugin: "nav2_costmap_2d::ObstacleLayer"
|
||||
enabled: True
|
||||
observation_sources: scan
|
||||
scan:
|
||||
topic: /scan_no_nan
|
||||
max_obstacle_height: 2.0
|
||||
clearing: True
|
||||
marking: True
|
||||
data_type: "LaserScan"
|
||||
raytrace_max_range: 10.0
|
||||
raytrace_min_range: 0.0
|
||||
obstacle_max_range: 9.5
|
||||
obstacle_min_range: 0.0
|
||||
static_layer:
|
||||
plugin: "nav2_costmap_2d::StaticLayer"
|
||||
map_subscribe_transient_local: True
|
||||
inflation_layer:
|
||||
plugin: "nav2_costmap_2d::InflationLayer"
|
||||
cost_scaling_factor: 3.0
|
||||
inflation_radius: 0.95
|
||||
always_send_full_costmap: True
|
||||
global_costmap_client:
|
||||
ros__parameters:
|
||||
use_sim_time: False
|
||||
global_costmap_rclcpp_node:
|
||||
ros__parameters:
|
||||
use_sim_time: False
|
||||
|
||||
map_server:
|
||||
ros__parameters:
|
||||
use_sim_time: False
|
||||
yaml_filename: "turtlebot3_world.yaml"
|
||||
|
||||
map_saver:
|
||||
ros__parameters:
|
||||
use_sim_time: False
|
||||
save_map_timeout: 5.0
|
||||
free_thresh_default: 0.25
|
||||
occupied_thresh_default: 0.65
|
||||
map_subscribe_transient_local: True
|
||||
|
||||
planner_server:
|
||||
ros__parameters:
|
||||
expected_planner_frequency: 2.0
|
||||
use_sim_time: False
|
||||
planner_plugins: ["GridBased"]
|
||||
GridBased:
|
||||
plugin: "nav2_navfn_planner/NavfnPlanner"
|
||||
tolerance: 0.5
|
||||
use_astar: false
|
||||
allow_unknown: true
|
||||
|
||||
planner_server_rclcpp_node:
|
||||
ros__parameters:
|
||||
use_sim_time: False
|
||||
|
||||
recoveries_server:
|
||||
ros__parameters:
|
||||
costmap_topic: local_costmap/costmap_raw
|
||||
footprint_topic: local_costmap/published_footprint
|
||||
cycle_frequency: 10.0
|
||||
recovery_plugins: ["spin", "backup", "wait"]
|
||||
spin:
|
||||
plugin: "nav2_recoveries/Spin"
|
||||
backup:
|
||||
plugin: "nav2_recoveries/BackUp"
|
||||
wait:
|
||||
plugin: "nav2_recoveries/Wait"
|
||||
global_frame: odom
|
||||
robot_base_frame: base_link
|
||||
transform_timeout: 0.1
|
||||
use_sim_time: False
|
||||
simulate_ahead_time: 2.0
|
||||
max_rotational_vel: 1.0
|
||||
min_rotational_vel: 0.4
|
||||
rotational_acc_lim: 3.2
|
||||
|
||||
robot_state_publisher:
|
||||
ros__parameters:
|
||||
use_sim_time: False
|
||||
|
||||
waypoint_follower:
|
||||
ros__parameters:
|
||||
loop_rate: 2
|
||||
stop_on_failure: false
|
||||
waypoint_task_executor_plugin: "wait_at_waypoint"
|
||||
wait_at_waypoint:
|
||||
plugin: "nav2_waypoint_follower::WaitAtWaypoint"
|
||||
enabled: True
|
||||
waypoint_pause_duration: 200
|
||||
|
||||
slam_toolbox:
|
||||
ros__parameters:
|
||||
|
||||
# Plugin params
|
||||
solver_plugin: solver_plugins::CeresSolver
|
||||
ceres_linear_solver: SPARSE_NORMAL_CHOLESKY
|
||||
ceres_preconditioner: SCHUR_JACOBI
|
||||
ceres_trust_strategy: LEVENBERG_MARQUARDT
|
||||
ceres_dogleg_type: TRADITIONAL_DOGLEG
|
||||
ceres_loss_function: None
|
||||
|
||||
base_frame: base_link
|
||||
map_update_interval: 0.1
|
||||
scan_topic: /scan_no_nan
|
||||
odom_topic: /odom
|
||||
|
||||
# if you'd like to immediately start continuing a map at a given pose
|
||||
# or at the dock, but they are mutually exclusive, if pose is given
|
||||
# will use pose
|
||||
#map_file_name: test_steve
|
||||
#map_start_pose: [0.0, 0.0, 0.0]
|
||||
#map_start_at_dock: true
|
||||
|
||||
debug_logging: false
|
||||
throttle_scans: 1
|
||||
transform_publish_period: 0.02 #if 0 never publishes odometry
|
||||
map_update_interval: 0.5
|
||||
resolution: 0.05
|
||||
max_laser_range: 100.0 #for rastering images
|
||||
minimum_time_interval: 0.5
|
||||
transform_timeout: 0.2
|
||||
tf_buffer_duration: 30.
|
||||
stack_size_to_use: 40000000 #// program needs a larger stack size to serialize large maps
|
||||
enable_interactive_mode: true
|
||||
|
||||
# General Parameters
|
||||
use_scan_matching: true
|
||||
use_scan_barycenter: true
|
||||
minimum_travel_distance: 0.5
|
||||
minimum_travel_heading: 0.5
|
||||
scan_buffer_size: 10
|
||||
scan_buffer_maximum_scan_distance: 10.0
|
||||
link_match_minimum_response_fine: 0.1
|
||||
link_scan_maximum_distance: 1.5
|
||||
loop_search_maximum_distance: 3.0
|
||||
do_loop_closing: true
|
||||
loop_match_minimum_chain_size: 10
|
||||
loop_match_maximum_variance_coarse: 3.0
|
||||
loop_match_minimum_response_coarse: 0.35
|
||||
loop_match_minimum_response_fine: 0.45
|
||||
|
||||
# Correlation Parameters - Correlation Parameters
|
||||
correlation_search_space_dimension: 0.5
|
||||
correlation_search_space_resolution: 0.01
|
||||
correlation_search_space_smear_deviation: 0.1
|
||||
|
||||
# Correlation Parameters - Loop Closure Parameters
|
||||
loop_search_space_dimension: 8.0
|
||||
loop_search_space_resolution: 0.05
|
||||
loop_search_space_smear_deviation: 0.03
|
||||
|
||||
# Scan Matcher Parameters
|
||||
distance_variance_penalty: 0.5
|
||||
angle_variance_penalty: 1.0
|
||||
|
||||
fine_search_angle_offset: 0.00349
|
||||
coarse_search_angle_offset: 0.349
|
||||
coarse_angle_resolution: 0.0349
|
||||
minimum_angle_penalty: 0.9
|
||||
minimum_distance_penalty: 0.5
|
||||
use_response_expansion: true
|
49
src/dcaitirobot/.gitignore
vendored
@ -1,49 +0,0 @@
|
||||
devel/
|
||||
logs/
|
||||
install/
|
||||
build/
|
||||
bin/
|
||||
log/
|
||||
msg_gen/
|
||||
srv_gen/
|
||||
msg/*Action.msg
|
||||
msg/*ActionFeedback.msg
|
||||
msg/*ActionGoal.msg
|
||||
msg/*ActionResult.msg
|
||||
msg/*Feedback.msg
|
||||
msg/*Goal.msg
|
||||
msg/*Result.msg
|
||||
msg/_*.py
|
||||
build_isolated/
|
||||
devel_isolated/
|
||||
|
||||
# Generated by dynamic reconfigure
|
||||
*.cfgc
|
||||
/cfg/cpp/
|
||||
/cfg/*.py
|
||||
|
||||
# Ignore generated docs
|
||||
*.dox
|
||||
*.wikidoc
|
||||
|
||||
# eclipse stuff
|
||||
.project
|
||||
.cproject
|
||||
|
||||
# qcreator stuff
|
||||
CMakeLists.txt.user
|
||||
|
||||
srv/_*.py
|
||||
*.pcd
|
||||
*.pyc
|
||||
qtcreator-*
|
||||
*.user
|
||||
|
||||
/planning/cfg
|
||||
/planning/docs
|
||||
/planning/src
|
||||
|
||||
*~
|
||||
|
||||
# Emacs
|
||||
.#*
|
@ -1,42 +0,0 @@
|
||||
import numpy as np
|
||||
import rclpy
|
||||
from rclpy.node import Node
|
||||
from sensor_msgs.msg import LaserScan
|
||||
import geometry_msgs.msg as gm
|
||||
|
||||
|
||||
class TF2PublisherNode(Node):
|
||||
""" The purpose of this node is to modify the LaserScan produced by velodyne so as to be compatible with slam_toolbox.
|
||||
It seems there is an off-by-one error in slam_toolbox calculating the number of expected points in the scan,
|
||||
resulting in warnings that /scan contains fewer points than expected.
|
||||
"""
|
||||
def __init__(self):
|
||||
super().__init__('nanhandler')
|
||||
|
||||
self.create_subscription(LaserScan, "/scan", self.callback, 1)
|
||||
self.pub = self.create_publisher(LaserScan, "/scan_no_nan", 1)
|
||||
def callback(self, msg):
|
||||
print(msg.ranges[0])
|
||||
|
||||
msg.ranges[0] = float("inf")
|
||||
msg.intensities[0] = 0.0
|
||||
|
||||
msg.ranges.append(float("inf"))
|
||||
msg.intensities.append(0.0)
|
||||
|
||||
self.pub.publish(msg)
|
||||
|
||||
|
||||
|
||||
def main(args=None):
|
||||
rclpy.init(args=args)
|
||||
|
||||
tf2_publisher = TF2PublisherNode()
|
||||
rclpy.spin(tf2_publisher)
|
||||
|
||||
tf2_publisher.destroy_node()
|
||||
rclpy.shutdown()
|
||||
|
||||
|
||||
if __name__ == '__main__':
|
||||
main()
|
@ -1,276 +0,0 @@
|
||||
from math import atan2, degrees, sqrt
|
||||
from struct import Struct
|
||||
from time import sleep
|
||||
from typing import List
|
||||
|
||||
import rclpy
|
||||
from rclpy.context import Context
|
||||
from rclpy.node import Node
|
||||
from rclpy.parameter import Parameter
|
||||
from sensor_msgs.msg import Joy
|
||||
|
||||
|
||||
class JSEvent(object):
|
||||
"""A joystick even class (struct)
|
||||
|
||||
struct js_event_t
|
||||
{
|
||||
uint32_t time;
|
||||
int16_t value;
|
||||
uint8_t type;
|
||||
uint8_t id;
|
||||
};
|
||||
|
||||
Takes in raw bytes from a file.read(JS_EVENT_SIZE) call.
|
||||
|
||||
Also defines AXIS and BUTTON ids
|
||||
"""
|
||||
|
||||
JS_EVENT_SIZE = 8 # 64 bits is 8 bytes
|
||||
EVENT_BUTTON = 0x01
|
||||
EVENT_AXIS = 0x02
|
||||
EVENT_INIT = 0x80
|
||||
MAX_AXIS_COUNT = 27
|
||||
MAX_BUTTON_COUNT = 18
|
||||
AXIS_COUNT = 26
|
||||
BUTTON_COUNT = 17
|
||||
|
||||
AXIS_LEFT_STICK_HORIZONTAL = 0
|
||||
AXIS_LEFT_STICK_VERTICAL = 1
|
||||
AXIS_RIGHT_STICK_HORIZONTAL = 2
|
||||
AXIS_RIGHT_STICK_VERTICAL = 3
|
||||
AXIS_DPAD_UP = 8
|
||||
AXIS_DPAD_RIGHT = 9
|
||||
AXIS_DPAD_DOWN = 10
|
||||
AXIS_DPAD_LEFT = 11 # who knows what the left value should actually be...
|
||||
AXIS_LEFT_TRIGGER = 12
|
||||
AXIS_RIGHT_TRIGGER = 13
|
||||
AXIS_LEFT_BUMPER = 14
|
||||
AXIS_RIGHT_BUMPER = 15
|
||||
AXIS_TRIANGLE = 16
|
||||
AXIS_CIRCLE = 17
|
||||
AXIS_X = 18
|
||||
AXIS_SQUARE = 19
|
||||
AXIS_ACCEL_X = 23 # note: left is positive, right is negative
|
||||
AXIS_ACCEL_Y = 24 # note: back is positive, forward is negative
|
||||
AXIS_ACCEL_Z = 25 # note: can't tell what sign is what
|
||||
|
||||
BUTTON_SELECT = 0
|
||||
BUTTON_LEFT_JOYSTICK = 1
|
||||
BUTTON_RIGHT_JOYSTICK = 2
|
||||
BUTTON_START = 3
|
||||
BUTTON_DPAD_UP = 4
|
||||
BUTTON_DPAD_RIGHT = 5
|
||||
BUTTON_DPAD_DOWN = 6
|
||||
BUTTON_DPAD_LEFT = 7
|
||||
BUTTON_LEFT_TRIGGER = 8
|
||||
BUTTON_RIGHT_TRIGGER = 9
|
||||
BUTTON_LEFT_BUMPER = 10
|
||||
BUTTON_RIGHT_BUMPER = 11
|
||||
BUTTON_TRIANGLE = 12
|
||||
BUTTON_CIRCLE = 13
|
||||
BUTTON_X = 14
|
||||
BUTTON_SQUARE = 15
|
||||
BUTTON_PS3 = 16
|
||||
|
||||
def __init__(self, event_struct):
|
||||
# c.f. https://docs.python.org/3/library/struct.html#format-characters
|
||||
s = Struct("< I h B B")
|
||||
self.time, self.value, self.type, self.id = s.unpack(event_struct)
|
||||
# also c.f. Struct.pack()
|
||||
|
||||
# ignore non-input events
|
||||
self.type = self.type & ~self.EVENT_INIT
|
||||
|
||||
def __repr__(self):
|
||||
struct = "struct js_event_t\n{"
|
||||
# struct += '\n\tuint32_t time : {}'.format(self.time)
|
||||
struct += "\n\tint16_t value : {}".format(self.value)
|
||||
struct += "\n\tuint8_t type : {}".format(hex(self.type))
|
||||
struct += "\n\tuint8_t id : {}".format(self.id)
|
||||
struct += "\n};\n"
|
||||
return struct
|
||||
|
||||
|
||||
class Joystick(object):
|
||||
def __init__(self, js_file="/dev/input/js1"):
|
||||
# note names beginning with `__` are enforced as private
|
||||
self.file = open(js_file, "rb")
|
||||
# since we're using ID's as indices, account for 0 based indices
|
||||
self.__axis_values = [0] * (JSEvent.MAX_AXIS_COUNT + 1)
|
||||
# since we're using ID's as indices, account for 0 based indices
|
||||
self.__button_values = [0] * (JSEvent.MAX_BUTTON_COUNT + 1)
|
||||
|
||||
self.update_id = -1
|
||||
self.AxisUpdate = False
|
||||
self.ButtonUpdate = False
|
||||
self.event = None
|
||||
|
||||
def __del__(self):
|
||||
self.file.close()
|
||||
|
||||
def __enter__(self):
|
||||
return self
|
||||
|
||||
# __enter__ and __exit__ allow the context manager syntax
|
||||
# with Joystick() as js:
|
||||
# ...
|
||||
def __exit__(self, exc_type, exc_value, traceback):
|
||||
self.file.close()
|
||||
|
||||
def Update(self):
|
||||
self.event = JSEvent(self.file.read(JSEvent.JS_EVENT_SIZE))
|
||||
|
||||
if self.event.type == JSEvent.EVENT_AXIS:
|
||||
self.update_id = self.event.id
|
||||
self.AxisUpdate = True
|
||||
self.ButtonUpdate = False
|
||||
self.__axis_values[self.event.id] = self.event.value
|
||||
|
||||
if self.event.type == JSEvent.EVENT_BUTTON:
|
||||
self.update_id = self.event.id
|
||||
self.AxisUpdate = False
|
||||
self.ButtonUpdate = True
|
||||
self.__button_values[self.event.id] = self.event.value
|
||||
|
||||
def getButtonState(self, button_id):
|
||||
return self.__button_values[button_id]
|
||||
|
||||
def getAxisState(self, axis_id):
|
||||
return self.__axis_values[axis_id]
|
||||
|
||||
|
||||
class JoystickController(Joystick):
|
||||
"""An implementation specific controller that inherits a basic Joystick. Adds the capability to
|
||||
check for specific updates that you care about and then do something based on that.
|
||||
"""
|
||||
|
||||
def __init__(self, js_file="/dev/input/js0"):
|
||||
Joystick.__init__(self, js_file)
|
||||
# direction gives the direction of travel. Defined in terms of r and theta
|
||||
self.direction_vector = (0, 0)
|
||||
# rotation tells the robot to rotate x degrees
|
||||
self.rotation_vector = (0, 0)
|
||||
|
||||
def hasUpdate(self):
|
||||
return self.ButtonUpdate or self.AxisUpdate
|
||||
|
||||
def performUpdates(self):
|
||||
care_about_buttons = [
|
||||
JSEvent.BUTTON_SELECT,
|
||||
JSEvent.BUTTON_LEFT_JOYSTICK,
|
||||
JSEvent.BUTTON_RIGHT_JOYSTICK,
|
||||
JSEvent.BUTTON_START,
|
||||
JSEvent.BUTTON_DPAD_UP,
|
||||
JSEvent.BUTTON_DPAD_RIGHT,
|
||||
JSEvent.BUTTON_DPAD_DOWN,
|
||||
JSEvent.BUTTON_DPAD_LEFT,
|
||||
JSEvent.BUTTON_LEFT_TRIGGER,
|
||||
JSEvent.BUTTON_RIGHT_TRIGGER,
|
||||
JSEvent.BUTTON_LEFT_BUMPER,
|
||||
JSEvent.BUTTON_RIGHT_BUMPER,
|
||||
JSEvent.BUTTON_TRIANGLE,
|
||||
JSEvent.BUTTON_CIRCLE,
|
||||
JSEvent.BUTTON_X,
|
||||
JSEvent.BUTTON_SQUARE,
|
||||
JSEvent.BUTTON_PS3,
|
||||
]
|
||||
care_about_axes = [
|
||||
JSEvent.AXIS_LEFT_STICK_HORIZONTAL,
|
||||
JSEvent.AXIS_LEFT_STICK_VERTICAL,
|
||||
JSEvent.AXIS_RIGHT_STICK_HORIZONTAL,
|
||||
JSEvent.AXIS_RIGHT_STICK_VERTICAL,
|
||||
JSEvent.AXIS_DPAD_UP,
|
||||
JSEvent.AXIS_DPAD_LEFT,
|
||||
JSEvent.AXIS_DPAD_RIGHT,
|
||||
JSEvent.AXIS_DPAD_DOWN,
|
||||
JSEvent.AXIS_LEFT_TRIGGER,
|
||||
JSEvent.AXIS_RIGHT_TRIGGER,
|
||||
JSEvent.AXIS_LEFT_BUMPER,
|
||||
JSEvent.AXIS_RIGHT_BUMPER,
|
||||
JSEvent.AXIS_TRIANGLE,
|
||||
JSEvent.AXIS_CIRCLE,
|
||||
JSEvent.AXIS_X,
|
||||
JSEvent.AXIS_SQUARE,
|
||||
JSEvent.AXIS_ACCEL_X,
|
||||
JSEvent.AXIS_ACCEL_Y,
|
||||
JSEvent.AXIS_ACCEL_Z,
|
||||
]
|
||||
|
||||
if self.ButtonUpdate and self.update_id in care_about_buttons:
|
||||
self.__button_update()
|
||||
|
||||
if self.AxisUpdate and self.update_id in care_about_axes:
|
||||
self.__axis_update()
|
||||
|
||||
def __button_update(self):
|
||||
pass
|
||||
|
||||
def __axis_update(self):
|
||||
pass
|
||||
|
||||
class JoyNode(Node):
|
||||
def __init__(
|
||||
self,
|
||||
node_name: str,
|
||||
*,
|
||||
context: Context = None,
|
||||
cli_args: List[str] = None,
|
||||
namespace: str = None,
|
||||
use_global_arguments: bool = True,
|
||||
enable_rosout: bool = True,
|
||||
start_parameter_services: bool = True,
|
||||
parameter_overrides: List[Parameter] = None,
|
||||
allow_undeclared_parameters: bool = False,
|
||||
automatically_declare_parameters_from_overrides: bool = False,
|
||||
) -> None:
|
||||
super().__init__(
|
||||
node_name,
|
||||
context=context,
|
||||
cli_args=cli_args,
|
||||
namespace=namespace,
|
||||
use_global_arguments=use_global_arguments,
|
||||
enable_rosout=enable_rosout,
|
||||
start_parameter_services=start_parameter_services,
|
||||
parameter_overrides=parameter_overrides,
|
||||
allow_undeclared_parameters=allow_undeclared_parameters,
|
||||
automatically_declare_parameters_from_overrides=automatically_declare_parameters_from_overrides,
|
||||
)
|
||||
|
||||
self.pub = self.create_publisher(Joy, "/joy", 1)
|
||||
|
||||
def run(self):
|
||||
msg = Joy()
|
||||
msg.axes = [0.0, 0.0]
|
||||
msg.buttons = [0]
|
||||
with JoystickController("/dev/input/js0") as controller:
|
||||
while rclpy.ok():
|
||||
controller.Update()
|
||||
sleep(0.0001)
|
||||
|
||||
if controller.hasUpdate():
|
||||
hor = controller.getAxisState(JSEvent.AXIS_LEFT_STICK_HORIZONTAL)
|
||||
ver = controller.getAxisState(JSEvent.AXIS_LEFT_STICK_VERTICAL)
|
||||
|
||||
button_change_mode = controller.getButtonState(JSEvent.BUTTON_CIRCLE) # it says circle but it actually is dpad up
|
||||
self.get_logger().info(str(button_change_mode))
|
||||
|
||||
hor /= 2**15
|
||||
ver /= 2**15
|
||||
|
||||
msg.axes[JSEvent.AXIS_LEFT_STICK_HORIZONTAL] = hor
|
||||
msg.axes[JSEvent.AXIS_LEFT_STICK_VERTICAL] = ver
|
||||
msg.buttons[0] = button_change_mode
|
||||
|
||||
self.pub.publish(msg)
|
||||
|
||||
|
||||
def main(args=None):
|
||||
rclpy.init(args=args)
|
||||
node = JoyNode("test")
|
||||
node.run()
|
||||
rclpy.shutdown()
|
||||
|
||||
|
||||
if __name__ == "__main__":
|
||||
main()
|
@ -1,270 +0,0 @@
|
||||
import multiprocessing as mp
|
||||
import struct
|
||||
import threading
|
||||
import time
|
||||
from threading import Thread
|
||||
from typing import List
|
||||
|
||||
import rclpy
|
||||
import serial
|
||||
from rclpy.client import Client
|
||||
from rclpy.context import Context
|
||||
from rclpy.node import Node
|
||||
from rclpy.parameter import Parameter
|
||||
from std_msgs.msg import Float32MultiArray
|
||||
|
||||
start_time = time.time() * 1000
|
||||
|
||||
|
||||
def read_message_from_serial_stream_and_publish(stream: serial.Serial, speed_publisher):
|
||||
"""
|
||||
Read a message from the given serial stream.
|
||||
|
||||
:param stream: The serial stream.
|
||||
:return: The message.
|
||||
"""
|
||||
while stream.is_open:
|
||||
# Read until we find the start of a message.
|
||||
while stream.read(1) != b"\xAA":
|
||||
pass
|
||||
|
||||
# Read the rest of the message.
|
||||
frame_type = stream.read(1)
|
||||
if frame_type.hex() == "00":
|
||||
message_type = "measurement"
|
||||
elif frame_type.hex() == "20":
|
||||
message_type = "command"
|
||||
elif frame_type.hex() == "40":
|
||||
message_type = "response"
|
||||
else:
|
||||
# print("Invalid frame type: %s" % frame_type)
|
||||
continue
|
||||
|
||||
frame_length = stream.read(1)
|
||||
frame_component = stream.read(1)
|
||||
if frame_component.hex() == "00":
|
||||
component = "default"
|
||||
elif frame_component.hex() == "10":
|
||||
component = "left_motor"
|
||||
elif frame_component.hex() == "20":
|
||||
component = "right_motor"
|
||||
elif frame_component.hex() == "30":
|
||||
component = "both_motor"
|
||||
else:
|
||||
# print("Invalid frame component: %s" % frame_component.hex())
|
||||
continue
|
||||
|
||||
timestamp = stream.read(4)
|
||||
payload = stream.read(int.from_bytes(frame_length, byteorder="big"))
|
||||
|
||||
checksum = stream.read(2)
|
||||
|
||||
# Check the checksum.
|
||||
if sum(payload) != int.from_bytes(checksum, byteorder="big"):
|
||||
# print("Invalid checksum")
|
||||
# print(message_type,component,timestamp,payload,checksum)
|
||||
continue
|
||||
|
||||
# Handle message contents.
|
||||
if message_type == "measurement":
|
||||
if component == "left_motor":
|
||||
track_speed_left = struct.unpack(">f", payload[0:4])[0]
|
||||
elif component == "right_motor":
|
||||
track_speed_right = struct.unpack(">f", payload[0:4])[0]
|
||||
elif component == "both_motor":
|
||||
try:
|
||||
track_speed_right = struct.unpack(">f", payload[0:4])[0]
|
||||
track_speed_left = struct.unpack(">f", payload[4:8])[0]
|
||||
except Exception as e:
|
||||
# print(e)
|
||||
# print("Invalid payload: %s" % payload.hex())
|
||||
continue
|
||||
msg = Float32MultiArray()
|
||||
msg.data = [track_speed_left, track_speed_right]
|
||||
# msg.header.stamp = node.get_clock().now().to_msg()
|
||||
speed_publisher.publish(msg)
|
||||
elif message_type == "command":
|
||||
if payload == b"\x02":
|
||||
print("RESET_TIMESTAMP")
|
||||
global start_time
|
||||
start_time = time.time() * 1000
|
||||
|
||||
|
||||
def create_uart_message(
|
||||
message_type="default", component="default", payload=b"", timestamp=0
|
||||
):
|
||||
"""
|
||||
Create a UART message.
|
||||
|
||||
:param message_type: The type of the message.
|
||||
:param component: The component of the message.
|
||||
:param payload: The payload of the message.
|
||||
:param timestamp: The timestamp of the message.
|
||||
:return: The UART message.
|
||||
"""
|
||||
# Create the header.
|
||||
message_type_bytes = None
|
||||
if message_type == "measurement":
|
||||
message_type_bytes = b"\x00"
|
||||
elif message_type == "command":
|
||||
message_type_bytes = b"\x20"
|
||||
elif message_type == "response":
|
||||
message_type_bytes = b"\x40"
|
||||
else:
|
||||
raise ValueError("Invalid message type: %s" % message_type)
|
||||
|
||||
component_bytes = None
|
||||
if component == "default":
|
||||
component_bytes = b"\x00"
|
||||
elif component == "left_motor":
|
||||
component_bytes = b"\x10"
|
||||
elif component == "right_motor":
|
||||
component_bytes = b"\x20"
|
||||
elif component == "both_motor":
|
||||
component_bytes = b"\x30"
|
||||
else:
|
||||
raise ValueError("Invalid component: %s" % component)
|
||||
|
||||
# Create the payload.
|
||||
payload = bytearray(payload)
|
||||
|
||||
# Create the timestamp.
|
||||
timestamp = bytearray(timestamp.to_bytes(4, byteorder="big"))
|
||||
|
||||
# Create the checksum.
|
||||
checksum = bytearray(sum(payload).to_bytes(2, byteorder="little"))
|
||||
|
||||
# Create the message.
|
||||
message = bytearray()
|
||||
message.append(0xAA)
|
||||
message.extend(message_type_bytes)
|
||||
message.extend(len(payload).to_bytes(1, byteorder="big"))
|
||||
message.extend(component_bytes)
|
||||
message.extend(timestamp)
|
||||
message.extend(payload)
|
||||
message.extend(checksum)
|
||||
|
||||
# print(''.join([ "%02x" % b for b in message ]))
|
||||
|
||||
return message
|
||||
|
||||
|
||||
class ROS2UARTNode(Node):
|
||||
def __init__(
|
||||
self,
|
||||
node_name: str,
|
||||
ser: serial.Serial,
|
||||
*,
|
||||
context: Context = None,
|
||||
cli_args: List[str] = None,
|
||||
namespace: str = None,
|
||||
use_global_arguments: bool = True,
|
||||
enable_rosout: bool = True,
|
||||
start_parameter_services: bool = True,
|
||||
parameter_overrides: List[Parameter] = None,
|
||||
allow_undeclared_parameters: bool = False,
|
||||
automatically_declare_parameters_from_overrides: bool = False
|
||||
) -> None:
|
||||
super().__init__(
|
||||
node_name,
|
||||
context=context,
|
||||
cli_args=cli_args,
|
||||
namespace=namespace,
|
||||
use_global_arguments=use_global_arguments,
|
||||
enable_rosout=enable_rosout,
|
||||
start_parameter_services=start_parameter_services,
|
||||
parameter_overrides=parameter_overrides,
|
||||
allow_undeclared_parameters=allow_undeclared_parameters,
|
||||
automatically_declare_parameters_from_overrides=automatically_declare_parameters_from_overrides,
|
||||
)
|
||||
self.create_subscription(Float32MultiArray, "/track_speeds", self.callback, 1)
|
||||
self.left_speed = 0
|
||||
self.right_speed = 0
|
||||
|
||||
self.ser = ser
|
||||
|
||||
def callback(self, msg: Float32MultiArray) -> None:
|
||||
print(msg.data)
|
||||
assert len(msg.data) == 2
|
||||
self.left_speed, self.right_speed = msg.data
|
||||
self.left_speed /= 1
|
||||
self.right_speed /= 1
|
||||
left_byte = struct.pack(">f", self.left_speed)
|
||||
right_byte = struct.pack(">f", self.right_speed)
|
||||
|
||||
self.ser.write(
|
||||
create_uart_message(
|
||||
message_type="command",
|
||||
component="both_motor",
|
||||
payload=b"\x01" + left_byte + right_byte,
|
||||
timestamp=0,
|
||||
)
|
||||
)
|
||||
self.ser.flush()
|
||||
|
||||
|
||||
class UART2ROSNode(Node):
|
||||
def __init__(
|
||||
self,
|
||||
node_name: str,
|
||||
ser: serial.Serial,
|
||||
*,
|
||||
context: Context = None,
|
||||
cli_args: List[str] = None,
|
||||
namespace: str = None,
|
||||
use_global_arguments: bool = True,
|
||||
enable_rosout: bool = True,
|
||||
start_parameter_services: bool = True,
|
||||
parameter_overrides: List[Parameter] = None,
|
||||
allow_undeclared_parameters: bool = False,
|
||||
automatically_declare_parameters_from_overrides: bool = False
|
||||
) -> None:
|
||||
super().__init__(
|
||||
node_name,
|
||||
context=context,
|
||||
cli_args=cli_args,
|
||||
namespace=namespace,
|
||||
use_global_arguments=use_global_arguments,
|
||||
enable_rosout=enable_rosout,
|
||||
start_parameter_services=start_parameter_services,
|
||||
parameter_overrides=parameter_overrides,
|
||||
allow_undeclared_parameters=allow_undeclared_parameters,
|
||||
automatically_declare_parameters_from_overrides=automatically_declare_parameters_from_overrides,
|
||||
)
|
||||
self.speed_publisher = self.create_publisher(Float32MultiArray, "topic", 10)
|
||||
self.ser = ser
|
||||
|
||||
read_message_from_serial_stream_and_publish()
|
||||
|
||||
def destroy_node(self) -> bool:
|
||||
self.process.join()
|
||||
return super().destroy_node()
|
||||
|
||||
|
||||
def main(args=None) -> None:
|
||||
with serial.Serial("/dev/ttyUSB1", 115200, timeout=0.001) as ser:
|
||||
rclpy.init(args=args)
|
||||
ros2uart = ROS2UARTNode(node_name="ros2uart", ser=ser)
|
||||
# uart2ros = UART2ROSNode(node_name='uart2ros', ser=ser)
|
||||
|
||||
executor = rclpy.executors.MultiThreadedExecutor()
|
||||
# executor.add_node(uart2ros)
|
||||
executor.add_node(ros2uart)
|
||||
executor_thread = threading.Thread(target=executor.spin, daemon=True)
|
||||
executor_thread.start()
|
||||
|
||||
# loop while not interrupted
|
||||
curr_time = time.time()
|
||||
rate = ros2uart.create_rate(2)
|
||||
try:
|
||||
while rclpy.ok():
|
||||
print("Help me body, you are my only hope")
|
||||
rate.sleep()
|
||||
except KeyboardInterrupt:
|
||||
pass
|
||||
rclpy.shutdown()
|
||||
executor_thread.join()
|
||||
|
||||
|
||||
if __name__ == "__main__":
|
||||
main()
|
@ -1,105 +0,0 @@
|
||||
"""
|
||||
This file is not required anymore. It was our first, naive approach to translate Joy messages to track speeds for the robot.
|
||||
It is referenced in the project report, which is why we decided to keep it in the repo.
|
||||
"""
|
||||
|
||||
|
||||
import math
|
||||
from typing import List
|
||||
|
||||
import numpy as np
|
||||
import rclpy
|
||||
from rclpy.context import Context
|
||||
from rclpy.node import Node
|
||||
from rclpy.parameter import Parameter
|
||||
from sensor_msgs.msg import Joy
|
||||
from std_msgs.msg import Float32MultiArray
|
||||
|
||||
|
||||
def calc_left_power(angle: float) -> float:
|
||||
angle_deg = math.degrees(angle)
|
||||
if -180 <= angle_deg < -90:
|
||||
return 2 / 90 * (angle_deg + 180) - 1
|
||||
elif -90 <= angle_deg < 0:
|
||||
return 1
|
||||
elif 0 <= angle_deg < 90:
|
||||
return -2 / 90 * angle_deg + 1
|
||||
elif 90 <= angle_deg <= 180:
|
||||
return -1
|
||||
|
||||
|
||||
def calc_right_power(angle: float) -> float:
|
||||
angle_deg = math.degrees(angle)
|
||||
if -180 <= angle_deg < -90:
|
||||
return -1
|
||||
elif -90 <= angle_deg < 0:
|
||||
return 2 / 90 * (angle_deg + 90) - 1
|
||||
elif 0 <= angle_deg < 90:
|
||||
return 1
|
||||
elif 90 <= angle_deg <= 180:
|
||||
return -2 / 90 * (angle_deg - 90) + 1
|
||||
|
||||
|
||||
def calc_power_from_euclidean_joystick(x, y):
|
||||
x, y = y, -x # rotate 90 so that up is 0 degress
|
||||
r = np.linalg.norm([x, y]) / np.sqrt(2)
|
||||
angle = np.arctan2(y, x)
|
||||
|
||||
return calc_left_power(angle) * r, calc_right_power(angle) * r
|
||||
|
||||
|
||||
class JoystickSpeedDistributorNode(Node):
|
||||
def __init__(
|
||||
self,
|
||||
node_name: str,
|
||||
*,
|
||||
context: Context = None,
|
||||
cli_args: List[str] = None,
|
||||
namespace: str = None,
|
||||
use_global_arguments: bool = True,
|
||||
enable_rosout: bool = True,
|
||||
start_parameter_services: bool = True,
|
||||
parameter_overrides: List[Parameter] = None,
|
||||
allow_undeclared_parameters: bool = False,
|
||||
automatically_declare_parameters_from_overrides: bool = False
|
||||
) -> None:
|
||||
super().__init__(
|
||||
node_name,
|
||||
context=context,
|
||||
cli_args=cli_args,
|
||||
namespace=namespace,
|
||||
use_global_arguments=use_global_arguments,
|
||||
enable_rosout=enable_rosout,
|
||||
start_parameter_services=start_parameter_services,
|
||||
parameter_overrides=parameter_overrides,
|
||||
allow_undeclared_parameters=allow_undeclared_parameters,
|
||||
automatically_declare_parameters_from_overrides=automatically_declare_parameters_from_overrides,
|
||||
)
|
||||
self.l = 0.1
|
||||
|
||||
self.create_subscription(Joy, "/joy", self.joy_callback, 1)
|
||||
|
||||
self.pub = self.create_publisher(Float32MultiArray, "/track_speeds", 1)
|
||||
|
||||
def joy_callback(self, joy_message):
|
||||
x, y = joy_message.axes[:2]
|
||||
y = -y
|
||||
|
||||
powers = calc_power_from_euclidean_joystick(x, y)
|
||||
|
||||
msg = Float32MultiArray()
|
||||
|
||||
msg.data = list(map(float, powers))
|
||||
|
||||
self.pub.publish(msg)
|
||||
|
||||
|
||||
def main(args=None) -> None:
|
||||
rclpy.init(args=args)
|
||||
node = JoystickSpeedDistributorNode("speed_distributor")
|
||||
rclpy.spin(node)
|
||||
rclpy.shutdown()
|
||||
|
||||
|
||||
if __name__ == "__main__":
|
||||
main()
|
@ -1,106 +0,0 @@
|
||||
import rclpy
|
||||
from rclpy.node import Node
|
||||
|
||||
from geometry_msgs.msg import Twist
|
||||
from std_msgs.msg import String
|
||||
from sensor_msgs.msg import Joy
|
||||
|
||||
import numpy as np
|
||||
|
||||
SCALE_LINEAR_VELOCITY = 0.2
|
||||
SCALE_ANGULAR_VELOCITY = 0.7
|
||||
PUBLISH_FREQUENCY_HZ = 30
|
||||
|
||||
SMOOTH_WEIGHTS = np.array([1, 2, 4, 10, 20])
|
||||
|
||||
|
||||
class TwistPublisher(Node):
|
||||
"""
|
||||
This node serves as a bridge between the Joy messages published from the PS3 controller
|
||||
interface in joy.py and the Twist messages expected by ros_control.
|
||||
"""
|
||||
def __init__(
|
||||
self,
|
||||
smooth_weights=np.ones(5),
|
||||
linear_scale=1.0,
|
||||
angular_scale=1.0,
|
||||
publish_frequency_hz=30,
|
||||
):
|
||||
super().__init__("twist_publisher")
|
||||
|
||||
self.mode = "manual"
|
||||
|
||||
self.linear_window = np.zeros(smooth_weights.shape[0])
|
||||
self.angular_window = np.zeros(smooth_weights.shape[0])
|
||||
self.linear_recent = 0.0
|
||||
self.angular_recent = 0.0
|
||||
|
||||
self.linear_out = 0.0
|
||||
self.angular_out = 0.0
|
||||
|
||||
self.weights = smooth_weights / smooth_weights.sum()
|
||||
self.window_size = smooth_weights.shape[0]
|
||||
|
||||
self.linear_scale = linear_scale
|
||||
self.angular_scale = angular_scale
|
||||
|
||||
self.publisher_2 = self.create_publisher(Twist, "/cmd_vel_joystick", 1)
|
||||
|
||||
self.create_subscription(Joy, "/joy", self.joy_callback, 1)
|
||||
self.timer = self.create_timer(1 / publish_frequency_hz, self.timer_callback)
|
||||
|
||||
def joy_callback(self, joy_message):
|
||||
x, y = joy_message.axes[:2]
|
||||
self.linear_recent = -y * SCALE_LINEAR_VELOCITY
|
||||
self.angular_recent = x * SCALE_ANGULAR_VELOCITY
|
||||
|
||||
if joy_message.buttons[0]:
|
||||
self.mode = "manual" if self.mode == "auto" else "auto"
|
||||
self.get_logger().info(f"Switching to {self.mode!r} mode")
|
||||
|
||||
|
||||
def update_smooth_window(self):
|
||||
self.linear_window = np.append(self.linear_window, self.linear_recent)[
|
||||
-self.window_size :
|
||||
]
|
||||
self.angular_window = np.append(self.angular_window, self.angular_recent)[
|
||||
-self.window_size :
|
||||
]
|
||||
|
||||
def calc_smooth_speed(self):
|
||||
self.linear_out = np.average(self.linear_window, weights=self.weights)
|
||||
self.angular_out = np.average(self.angular_window, weights=self.weights)
|
||||
|
||||
def timer_callback(self):
|
||||
|
||||
if self.mode != "manual":
|
||||
return
|
||||
|
||||
msg = Twist()
|
||||
|
||||
self.update_smooth_window()
|
||||
self.calc_smooth_speed()
|
||||
|
||||
msg.linear.x = self.linear_out
|
||||
msg.angular.z = self.angular_out
|
||||
self.publisher_2.publish(msg)
|
||||
|
||||
|
||||
def main(args=None):
|
||||
rclpy.init(args=args)
|
||||
|
||||
minimal_publisher = TwistPublisher(
|
||||
SMOOTH_WEIGHTS,
|
||||
SCALE_LINEAR_VELOCITY,
|
||||
SCALE_ANGULAR_VELOCITY,
|
||||
PUBLISH_FREQUENCY_HZ,
|
||||
)
|
||||
|
||||
rclpy.spin(minimal_publisher)
|
||||
|
||||
minimal_publisher.destroy_node()
|
||||
rclpy.shutdown()
|
||||
|
||||
|
||||
if __name__ == "__main__":
|
||||
main()
|
5
src/dcaitirobot/embedded/.gitignore
vendored
@ -1,5 +0,0 @@
|
||||
.pio
|
||||
.vscode/.browse.c_cpp.db*
|
||||
.vscode/c_cpp_properties.json
|
||||
.vscode/launch.json
|
||||
.vscode/ipch
|
10
src/dcaitirobot/embedded/.vscode/extensions.json
vendored
@ -1,10 +0,0 @@
|
||||
{
|
||||
// See http://go.microsoft.com/fwlink/?LinkId=827846
|
||||
// for the documentation about the extensions.json format
|
||||
"recommendations": [
|
||||
"platformio.platformio-ide"
|
||||
],
|
||||
"unwantedRecommendations": [
|
||||
"ms-vscode.cpptools-extension-pack"
|
||||
]
|
||||
}
|
@ -1 +0,0 @@
|
||||
# DCAITI
|
@ -1,94 +0,0 @@
|
||||
<!DOCTYPE html PUBLIC "-//W3C//DTD XHTML 1.0 Transitional//EN" "https://www.w3.org/TR/xhtml1/DTD/xhtml1-transitional.dtd">
|
||||
<html xmlns="http://www.w3.org/1999/xhtml">
|
||||
<head>
|
||||
<meta http-equiv="Content-Type" content="text/xhtml;charset=UTF-8"/>
|
||||
<meta http-equiv="X-UA-Compatible" content="IE=9"/>
|
||||
<meta name="generator" content="Doxygen 1.9.1"/>
|
||||
<meta name="viewport" content="width=device-width, initial-scale=1"/>
|
||||
<title>DCAITI Robot Hardware: lib/MotorWheel/MotorWheel.cpp File Reference</title>
|
||||
<link href="tabs.css" rel="stylesheet" type="text/css"/>
|
||||
<script type="text/javascript" src="jquery.js"></script>
|
||||
<script type="text/javascript" src="dynsections.js"></script>
|
||||
<link href="search/search.css" rel="stylesheet" type="text/css"/>
|
||||
<script type="text/javascript" src="search/searchdata.js"></script>
|
||||
<script type="text/javascript" src="search/search.js"></script>
|
||||
<link href="doxygen.css" rel="stylesheet" type="text/css" />
|
||||
</head>
|
||||
<body>
|
||||
<div id="top"><!-- do not remove this div, it is closed by doxygen! -->
|
||||
<div id="titlearea">
|
||||
<table cellspacing="0" cellpadding="0">
|
||||
<tbody>
|
||||
<tr style="height: 56px;">
|
||||
<td id="projectalign" style="padding-left: 0.5em;">
|
||||
<div id="projectname">DCAITI Robot Hardware
|
||||
 <span id="projectnumber">1.0</span>
|
||||
</div>
|
||||
</td>
|
||||
</tr>
|
||||
</tbody>
|
||||
</table>
|
||||
</div>
|
||||
<!-- end header part -->
|
||||
<!-- Generated by Doxygen 1.9.1 -->
|
||||
<script type="text/javascript">
|
||||
/* @license magnet:?xt=urn:btih:cf05388f2679ee054f2beb29a391d25f4e673ac3&dn=gpl-2.0.txt GPL-v2 */
|
||||
var searchBox = new SearchBox("searchBox", "search",false,'Search','.html');
|
||||
/* @license-end */
|
||||
</script>
|
||||
<script type="text/javascript" src="menudata.js"></script>
|
||||
<script type="text/javascript" src="menu.js"></script>
|
||||
<script type="text/javascript">
|
||||
/* @license magnet:?xt=urn:btih:cf05388f2679ee054f2beb29a391d25f4e673ac3&dn=gpl-2.0.txt GPL-v2 */
|
||||
$(function() {
|
||||
initMenu('',true,false,'search.php','Search');
|
||||
$(document).ready(function() { init_search(); });
|
||||
});
|
||||
/* @license-end */</script>
|
||||
<div id="main-nav"></div>
|
||||
<!-- window showing the filter options -->
|
||||
<div id="MSearchSelectWindow"
|
||||
onmouseover="return searchBox.OnSearchSelectShow()"
|
||||
onmouseout="return searchBox.OnSearchSelectHide()"
|
||||
onkeydown="return searchBox.OnSearchSelectKey(event)">
|
||||
</div>
|
||||
|
||||
<!-- iframe showing the search results (closed by default) -->
|
||||
<div id="MSearchResultsWindow">
|
||||
<iframe src="javascript:void(0)" frameborder="0"
|
||||
name="MSearchResults" id="MSearchResults">
|
||||
</iframe>
|
||||
</div>
|
||||
|
||||
<div id="nav-path" class="navpath">
|
||||
<ul>
|
||||
<li class="navelem"><a class="el" href="dir_97aefd0d527b934f1d99a682da8fe6a9.html">lib</a></li><li class="navelem"><a class="el" href="dir_10c6c21535d653b7c685bbf5a23d61f7.html">MotorWheel</a></li> </ul>
|
||||
</div>
|
||||
</div><!-- top -->
|
||||
<div class="header">
|
||||
<div class="headertitle">
|
||||
<div class="title">MotorWheel.cpp File Reference</div> </div>
|
||||
</div><!--header-->
|
||||
<div class="contents">
|
||||
<div class="textblock"><code>#include <<a class="el" href="MotorWheel_8h_source.html">MotorWheel.h</a>></code><br />
|
||||
</div><div class="textblock"><div class="dynheader">
|
||||
Include dependency graph for MotorWheel.cpp:</div>
|
||||
<div class="dyncontent">
|
||||
<div class="center"><img src="MotorWheel_8cpp__incl.png" border="0" usemap="#alib_2MotorWheel_2MotorWheel_8cpp" alt=""/></div>
|
||||
<map name="alib_2MotorWheel_2MotorWheel_8cpp" id="alib_2MotorWheel_2MotorWheel_8cpp">
|
||||
<area shape="rect" title=" " alt="" coords="31,5,261,32"/>
|
||||
<area shape="rect" href="MotorWheel_8h.html" title=" " alt="" coords="89,80,203,107"/>
|
||||
<area shape="rect" href="PID__Beta6_8h.html" title=" " alt="" coords="29,155,130,181"/>
|
||||
<area shape="rect" href="PinChangeInt_8h.html" title=" " alt="" coords="154,155,274,181"/>
|
||||
<area shape="rect" title=" " alt="" coords="5,229,108,256"/>
|
||||
<area shape="rect" href="PinChangeIntConfig_8h.html" title=" " alt="" coords="133,229,295,256"/>
|
||||
<area shape="rect" title=" " alt="" coords="319,229,437,256"/>
|
||||
</map>
|
||||
</div>
|
||||
</div></div><!-- contents -->
|
||||
<!-- start footer part -->
|
||||
<hr class="footer"/><address class="footer"><small>
|
||||
Generated by <a href="https://www.doxygen.org/index.html"><img class="footer" src="doxygen.svg" width="104" height="31" alt="doxygen"/></a> 1.9.1
|
||||
</small></address>
|
||||
</body>
|
||||
</html>
|
@ -1,9 +0,0 @@
|
||||
<map id="lib/MotorWheel/MotorWheel.cpp" name="lib/MotorWheel/MotorWheel.cpp">
|
||||
<area shape="rect" id="node1" title=" " alt="" coords="31,5,261,32"/>
|
||||
<area shape="rect" id="node2" href="$MotorWheel_8h.html" title=" " alt="" coords="89,80,203,107"/>
|
||||
<area shape="rect" id="node3" href="$PID__Beta6_8h.html" title=" " alt="" coords="29,155,130,181"/>
|
||||
<area shape="rect" id="node4" href="$PinChangeInt_8h.html" title=" " alt="" coords="154,155,274,181"/>
|
||||
<area shape="rect" id="node5" title=" " alt="" coords="5,229,108,256"/>
|
||||
<area shape="rect" id="node6" href="$PinChangeIntConfig_8h.html" title=" " alt="" coords="133,229,295,256"/>
|
||||
<area shape="rect" id="node7" title=" " alt="" coords="319,229,437,256"/>
|
||||
</map>
|
@ -1 +0,0 @@
|
||||
19afef5d5b6c2d2aa9fa960ddf0e7ab0
|
Before Width: | Height: | Size: 13 KiB |
@ -1,521 +0,0 @@
|
||||
<!DOCTYPE html PUBLIC "-//W3C//DTD XHTML 1.0 Transitional//EN" "https://www.w3.org/TR/xhtml1/DTD/xhtml1-transitional.dtd">
|
||||
<html xmlns="http://www.w3.org/1999/xhtml">
|
||||
<head>
|
||||
<meta http-equiv="Content-Type" content="text/xhtml;charset=UTF-8"/>
|
||||
<meta http-equiv="X-UA-Compatible" content="IE=9"/>
|
||||
<meta name="generator" content="Doxygen 1.9.1"/>
|
||||
<meta name="viewport" content="width=device-width, initial-scale=1"/>
|
||||
<title>DCAITI Robot Hardware: lib/MotorWheel/MotorWheel.h File Reference</title>
|
||||
<link href="tabs.css" rel="stylesheet" type="text/css"/>
|
||||
<script type="text/javascript" src="jquery.js"></script>
|
||||
<script type="text/javascript" src="dynsections.js"></script>
|
||||
<link href="search/search.css" rel="stylesheet" type="text/css"/>
|
||||
<script type="text/javascript" src="search/searchdata.js"></script>
|
||||
<script type="text/javascript" src="search/search.js"></script>
|
||||
<link href="doxygen.css" rel="stylesheet" type="text/css" />
|
||||
</head>
|
||||
<body>
|
||||
<div id="top"><!-- do not remove this div, it is closed by doxygen! -->
|
||||
<div id="titlearea">
|
||||
<table cellspacing="0" cellpadding="0">
|
||||
<tbody>
|
||||
<tr style="height: 56px;">
|
||||
<td id="projectalign" style="padding-left: 0.5em;">
|
||||
<div id="projectname">DCAITI Robot Hardware
|
||||
 <span id="projectnumber">1.0</span>
|
||||
</div>
|
||||
</td>
|
||||
</tr>
|
||||
</tbody>
|
||||
</table>
|
||||
</div>
|
||||
<!-- end header part -->
|
||||
<!-- Generated by Doxygen 1.9.1 -->
|
||||
<script type="text/javascript">
|
||||
/* @license magnet:?xt=urn:btih:cf05388f2679ee054f2beb29a391d25f4e673ac3&dn=gpl-2.0.txt GPL-v2 */
|
||||
var searchBox = new SearchBox("searchBox", "search",false,'Search','.html');
|
||||
/* @license-end */
|
||||
</script>
|
||||
<script type="text/javascript" src="menudata.js"></script>
|
||||
<script type="text/javascript" src="menu.js"></script>
|
||||
<script type="text/javascript">
|
||||
/* @license magnet:?xt=urn:btih:cf05388f2679ee054f2beb29a391d25f4e673ac3&dn=gpl-2.0.txt GPL-v2 */
|
||||
$(function() {
|
||||
initMenu('',true,false,'search.php','Search');
|
||||
$(document).ready(function() { init_search(); });
|
||||
});
|
||||
/* @license-end */</script>
|
||||
<div id="main-nav"></div>
|
||||
<!-- window showing the filter options -->
|
||||
<div id="MSearchSelectWindow"
|
||||
onmouseover="return searchBox.OnSearchSelectShow()"
|
||||
onmouseout="return searchBox.OnSearchSelectHide()"
|
||||
onkeydown="return searchBox.OnSearchSelectKey(event)">
|
||||
</div>
|
||||
|
||||
<!-- iframe showing the search results (closed by default) -->
|
||||
<div id="MSearchResultsWindow">
|
||||
<iframe src="javascript:void(0)" frameborder="0"
|
||||
name="MSearchResults" id="MSearchResults">
|
||||
</iframe>
|
||||
</div>
|
||||
|
||||
<div id="nav-path" class="navpath">
|
||||
<ul>
|
||||
<li class="navelem"><a class="el" href="dir_97aefd0d527b934f1d99a682da8fe6a9.html">lib</a></li><li class="navelem"><a class="el" href="dir_10c6c21535d653b7c685bbf5a23d61f7.html">MotorWheel</a></li> </ul>
|
||||
</div>
|
||||
</div><!-- top -->
|
||||
<div class="header">
|
||||
<div class="summary">
|
||||
<a href="#nested-classes">Classes</a> |
|
||||
<a href="#define-members">Macros</a> </div>
|
||||
<div class="headertitle">
|
||||
<div class="title">MotorWheel.h File Reference</div> </div>
|
||||
</div><!--header-->
|
||||
<div class="contents">
|
||||
<div class="textblock"><code>#include <<a class="el" href="PID__Beta6_8h_source.html">PID_Beta6.h</a>></code><br />
|
||||
<code>#include <<a class="el" href="PinChangeInt_8h_source.html">PinChangeInt.h</a>></code><br />
|
||||
</div><div class="textblock"><div class="dynheader">
|
||||
Include dependency graph for MotorWheel.h:</div>
|
||||
<div class="dyncontent">
|
||||
<div class="center"><img src="MotorWheel_8h__incl.png" border="0" usemap="#alib_2MotorWheel_2MotorWheel_8h" alt=""/></div>
|
||||
<map name="alib_2MotorWheel_2MotorWheel_8h" id="alib_2MotorWheel_2MotorWheel_8h">
|
||||
<area shape="rect" title=" " alt="" coords="38,5,254,32"/>
|
||||
<area shape="rect" href="PID__Beta6_8h.html" title=" " alt="" coords="29,80,130,107"/>
|
||||
<area shape="rect" href="PinChangeInt_8h.html" title=" " alt="" coords="154,80,274,107"/>
|
||||
<area shape="rect" title=" " alt="" coords="5,155,108,181"/>
|
||||
<area shape="rect" href="PinChangeIntConfig_8h.html" title=" " alt="" coords="133,155,295,181"/>
|
||||
<area shape="rect" title=" " alt="" coords="319,155,437,181"/>
|
||||
</map>
|
||||
</div>
|
||||
</div><div class="textblock"><div class="dynheader">
|
||||
This graph shows which files directly or indirectly include this file:</div>
|
||||
<div class="dyncontent">
|
||||
<div class="center"><img src="MotorWheel_8h__dep__incl.png" border="0" usemap="#alib_2MotorWheel_2MotorWheel_8hdep" alt=""/></div>
|
||||
<map name="alib_2MotorWheel_2MotorWheel_8hdep" id="alib_2MotorWheel_2MotorWheel_8hdep">
|
||||
<area shape="rect" title=" " alt="" coords="397,5,613,32"/>
|
||||
<area shape="rect" href="UARTCom_8cpp.html" title=" " alt="" coords="5,80,248,107"/>
|
||||
<area shape="rect" href="UCommands_8cpp.html" title=" " alt="" coords="272,80,533,107"/>
|
||||
<area shape="rect" href="main_8cpp.html" title=" " alt="" coords="557,80,662,107"/>
|
||||
<area shape="rect" href="MotorWheel_8cpp.html" title=" " alt="" coords="686,80,917,107"/>
|
||||
</map>
|
||||
</div>
|
||||
</div>
|
||||
<p><a href="MotorWheel_8h_source.html">Go to the source code of this file.</a></p>
|
||||
<table class="memberdecls">
|
||||
<tr class="heading"><td colspan="2"><h2 class="groupheader"><a name="nested-classes"></a>
|
||||
Classes</h2></td></tr>
|
||||
<tr class="memitem:"><td class="memItemLeft" align="right" valign="top">struct  </td><td class="memItemRight" valign="bottom"><a class="el" href="structISRVars.html">ISRVars</a></td></tr>
|
||||
<tr class="separator:"><td class="memSeparator" colspan="2"> </td></tr>
|
||||
<tr class="memitem:"><td class="memItemLeft" align="right" valign="top">class  </td><td class="memItemRight" valign="bottom"><a class="el" href="classMotor.html">Motor</a></td></tr>
|
||||
<tr class="separator:"><td class="memSeparator" colspan="2"> </td></tr>
|
||||
<tr class="memitem:"><td class="memItemLeft" align="right" valign="top">class  </td><td class="memItemRight" valign="bottom"><a class="el" href="classGearedMotor.html">GearedMotor</a></td></tr>
|
||||
<tr class="separator:"><td class="memSeparator" colspan="2"> </td></tr>
|
||||
<tr class="memitem:"><td class="memItemLeft" align="right" valign="top">class  </td><td class="memItemRight" valign="bottom"><a class="el" href="classMotorWheel.html">MotorWheel</a></td></tr>
|
||||
<tr class="separator:"><td class="memSeparator" colspan="2"> </td></tr>
|
||||
</table><table class="memberdecls">
|
||||
<tr class="heading"><td colspan="2"><h2 class="groupheader"><a name="define-members"></a>
|
||||
Macros</h2></td></tr>
|
||||
<tr class="memitem:a4ba93a34cdd9c7b4d1f72021b449906e"><td class="memItemLeft" align="right" valign="top">#define </td><td class="memItemRight" valign="bottom"><a class="el" href="MotorWheel_8h.html#a4ba93a34cdd9c7b4d1f72021b449906e">DIR_ADVANCE</a>   HIGH</td></tr>
|
||||
<tr class="separator:a4ba93a34cdd9c7b4d1f72021b449906e"><td class="memSeparator" colspan="2"> </td></tr>
|
||||
<tr class="memitem:ad52f8b2bf56da6fe72ca2bf9da935ee7"><td class="memItemLeft" align="right" valign="top">#define </td><td class="memItemRight" valign="bottom"><a class="el" href="MotorWheel_8h.html#ad52f8b2bf56da6fe72ca2bf9da935ee7">DIR_BACKOFF</a>   LOW</td></tr>
|
||||
<tr class="separator:ad52f8b2bf56da6fe72ca2bf9da935ee7"><td class="memSeparator" colspan="2"> </td></tr>
|
||||
<tr class="memitem:adf4d6e9fc5cbf047c65ce74b4fa14117"><td class="memItemLeft" align="right" valign="top">#define </td><td class="memItemRight" valign="bottom"><a class="el" href="MotorWheel_8h.html#adf4d6e9fc5cbf047c65ce74b4fa14117">PIN_UNDEFINED</a>   255</td></tr>
|
||||
<tr class="separator:adf4d6e9fc5cbf047c65ce74b4fa14117"><td class="memSeparator" colspan="2"> </td></tr>
|
||||
<tr class="memitem:a2d979268f4539332ee9b1abc5b58e974"><td class="memItemLeft" align="right" valign="top">#define </td><td class="memItemRight" valign="bottom"><a class="el" href="MotorWheel_8h.html#a2d979268f4539332ee9b1abc5b58e974">REF_VOLT</a>   12</td></tr>
|
||||
<tr class="separator:a2d979268f4539332ee9b1abc5b58e974"><td class="memSeparator" colspan="2"> </td></tr>
|
||||
<tr class="memitem:a1df990f1a1fc97b95e8d53f719968026"><td class="memItemLeft" align="right" valign="top">#define </td><td class="memItemRight" valign="bottom"><a class="el" href="MotorWheel_8h.html#a1df990f1a1fc97b95e8d53f719968026">MAX_PWM</a>   255</td></tr>
|
||||
<tr class="separator:a1df990f1a1fc97b95e8d53f719968026"><td class="memSeparator" colspan="2"> </td></tr>
|
||||
<tr class="memitem:a86de85f5177dabb5ff712bf180db43aa"><td class="memItemLeft" align="right" valign="top">#define </td><td class="memItemRight" valign="bottom"><a class="el" href="MotorWheel_8h.html#a86de85f5177dabb5ff712bf180db43aa">TRIGGER</a>   CHANGE</td></tr>
|
||||
<tr class="separator:a86de85f5177dabb5ff712bf180db43aa"><td class="memSeparator" colspan="2"> </td></tr>
|
||||
<tr class="memitem:ad8f1771d4051eafad228df4d397d7e47"><td class="memItemLeft" align="right" valign="top">#define </td><td class="memItemRight" valign="bottom"><a class="el" href="MotorWheel_8h.html#ad8f1771d4051eafad228df4d397d7e47">CPR</a>   24</td></tr>
|
||||
<tr class="separator:ad8f1771d4051eafad228df4d397d7e47"><td class="memSeparator" colspan="2"> </td></tr>
|
||||
<tr class="memitem:a37aea0c86f1a366a15e54142dbcd0f45"><td class="memItemLeft" align="right" valign="top">#define </td><td class="memItemRight" valign="bottom"><a class="el" href="MotorWheel_8h.html#a37aea0c86f1a366a15e54142dbcd0f45">DIR_INVERSE</a>   !</td></tr>
|
||||
<tr class="separator:a37aea0c86f1a366a15e54142dbcd0f45"><td class="memSeparator" colspan="2"> </td></tr>
|
||||
<tr class="memitem:a545c3d33941dafc6ffd8cd9a61f6fca4"><td class="memItemLeft" align="right" valign="top">#define </td><td class="memItemRight" valign="bottom"><a class="el" href="MotorWheel_8h.html#a545c3d33941dafc6ffd8cd9a61f6fca4">REDUCTION_RATIO</a>   64</td></tr>
|
||||
<tr class="separator:a545c3d33941dafc6ffd8cd9a61f6fca4"><td class="memSeparator" colspan="2"> </td></tr>
|
||||
<tr class="memitem:a81d84c8ab20039cad6024ab239ee4086"><td class="memItemLeft" align="right" valign="top">#define </td><td class="memItemRight" valign="bottom"><a class="el" href="MotorWheel_8h.html#a81d84c8ab20039cad6024ab239ee4086">MAX_SPEEDRPM</a>   8000</td></tr>
|
||||
<tr class="separator:a81d84c8ab20039cad6024ab239ee4086"><td class="memSeparator" colspan="2"> </td></tr>
|
||||
<tr class="memitem:ac47b302f1b8d2a7a9c035c417247be76"><td class="memItemLeft" align="right" valign="top">#define </td><td class="memItemRight" valign="bottom"><a class="el" href="MotorWheel_8h.html#ac47b302f1b8d2a7a9c035c417247be76">SEC_PER_MIN</a>   60</td></tr>
|
||||
<tr class="separator:ac47b302f1b8d2a7a9c035c417247be76"><td class="memSeparator" colspan="2"> </td></tr>
|
||||
<tr class="memitem:a81bcea712b48d6bf8f7193e3de40404b"><td class="memItemLeft" align="right" valign="top">#define </td><td class="memItemRight" valign="bottom"><a class="el" href="MotorWheel_8h.html#a81bcea712b48d6bf8f7193e3de40404b">MICROS_PER_SEC</a>   1000000</td></tr>
|
||||
<tr class="separator:a81bcea712b48d6bf8f7193e3de40404b"><td class="memSeparator" colspan="2"> </td></tr>
|
||||
<tr class="memitem:a2ab9b66762dd6eb975292a7e83116bec"><td class="memItemLeft" align="right" valign="top">#define </td><td class="memItemRight" valign="bottom"><a class="el" href="MotorWheel_8h.html#a2ab9b66762dd6eb975292a7e83116bec">SPEEDPPS2SPEEDRPM</a>(freq)   ((unsigned long)(freq)*(<a class="el" href="MotorWheel_8h.html#ac47b302f1b8d2a7a9c035c417247be76">SEC_PER_MIN</a>)/(<a class="el" href="MotorWheel_8h.html#ad8f1771d4051eafad228df4d397d7e47">CPR</a>))</td></tr>
|
||||
<tr class="separator:a2ab9b66762dd6eb975292a7e83116bec"><td class="memSeparator" colspan="2"> </td></tr>
|
||||
<tr class="memitem:a73764abcca0b8bbf6bf355d9f1bab0b9"><td class="memItemLeft" align="right" valign="top">#define </td><td class="memItemRight" valign="bottom"><a class="el" href="MotorWheel_8h.html#a73764abcca0b8bbf6bf355d9f1bab0b9">KC</a>   0.31</td></tr>
|
||||
<tr class="separator:a73764abcca0b8bbf6bf355d9f1bab0b9"><td class="memSeparator" colspan="2"> </td></tr>
|
||||
<tr class="memitem:a73c066690ee81cb3f9c801205a237acd"><td class="memItemLeft" align="right" valign="top">#define </td><td class="memItemRight" valign="bottom"><a class="el" href="MotorWheel_8h.html#a73c066690ee81cb3f9c801205a237acd">TAUI</a>   0.02</td></tr>
|
||||
<tr class="separator:a73c066690ee81cb3f9c801205a237acd"><td class="memSeparator" colspan="2"> </td></tr>
|
||||
<tr class="memitem:a75450bf317fb4edd6c44dbe6b2ff7673"><td class="memItemLeft" align="right" valign="top">#define </td><td class="memItemRight" valign="bottom"><a class="el" href="MotorWheel_8h.html#a75450bf317fb4edd6c44dbe6b2ff7673">TAUD</a>   0.00</td></tr>
|
||||
<tr class="separator:a75450bf317fb4edd6c44dbe6b2ff7673"><td class="memSeparator" colspan="2"> </td></tr>
|
||||
<tr class="memitem:a755b9528bf80376f0476829e8078a0da"><td class="memItemLeft" align="right" valign="top">#define </td><td class="memItemRight" valign="bottom"><a class="el" href="MotorWheel_8h.html#a755b9528bf80376f0476829e8078a0da">SAMPLETIME</a>   5</td></tr>
|
||||
<tr class="separator:a755b9528bf80376f0476829e8078a0da"><td class="memSeparator" colspan="2"> </td></tr>
|
||||
<tr class="memitem:ab201ec4c4f600966de3779313f08d2c3"><td class="memItemLeft" align="right" valign="top">#define </td><td class="memItemRight" valign="bottom"><a class="el" href="MotorWheel_8h.html#ab201ec4c4f600966de3779313f08d2c3">Baudrate</a>   19200</td></tr>
|
||||
<tr class="separator:ab201ec4c4f600966de3779313f08d2c3"><td class="memSeparator" colspan="2"> </td></tr>
|
||||
<tr class="memitem:aa8f0efe0d1ee33354f41f8898d0ee8dd"><td class="memItemLeft" align="right" valign="top">#define </td><td class="memItemRight" valign="bottom"><a class="el" href="MotorWheel_8h.html#aa8f0efe0d1ee33354f41f8898d0ee8dd">debug</a>()   {}</td></tr>
|
||||
<tr class="separator:aa8f0efe0d1ee33354f41f8898d0ee8dd"><td class="memSeparator" colspan="2"> </td></tr>
|
||||
<tr class="memitem:a9812ffc02e34cfd1b5809ba2811a98ae"><td class="memItemLeft" align="right" valign="top">#define </td><td class="memItemRight" valign="bottom"><a class="el" href="MotorWheel_8h.html#a9812ffc02e34cfd1b5809ba2811a98ae">irqISR</a>(y, x)</td></tr>
|
||||
<tr class="separator:a9812ffc02e34cfd1b5809ba2811a98ae"><td class="memSeparator" colspan="2"> </td></tr>
|
||||
<tr class="memitem:a598a3330b3c21701223ee0ca14316eca"><td class="memItemLeft" align="right" valign="top">#define </td><td class="memItemRight" valign="bottom"><a class="el" href="MotorWheel_8h.html#a598a3330b3c21701223ee0ca14316eca">PI</a>   3.1416</td></tr>
|
||||
<tr class="separator:a598a3330b3c21701223ee0ca14316eca"><td class="memSeparator" colspan="2"> </td></tr>
|
||||
<tr class="memitem:a557b8031c21a790194ec252c281dc404"><td class="memItemLeft" align="right" valign="top">#define </td><td class="memItemRight" valign="bottom"><a class="el" href="MotorWheel_8h.html#a557b8031c21a790194ec252c281dc404">CIRMM</a>   314</td></tr>
|
||||
<tr class="separator:a557b8031c21a790194ec252c281dc404"><td class="memSeparator" colspan="2"> </td></tr>
|
||||
</table>
|
||||
<h2 class="groupheader">Macro Definition Documentation</h2>
|
||||
<a id="ab201ec4c4f600966de3779313f08d2c3"></a>
|
||||
<h2 class="memtitle"><span class="permalink"><a href="#ab201ec4c4f600966de3779313f08d2c3">◆ </a></span>Baudrate</h2>
|
||||
|
||||
<div class="memitem">
|
||||
<div class="memproto">
|
||||
<table class="memname">
|
||||
<tr>
|
||||
<td class="memname">#define Baudrate   19200</td>
|
||||
</tr>
|
||||
</table>
|
||||
</div><div class="memdoc">
|
||||
|
||||
</div>
|
||||
</div>
|
||||
<a id="a557b8031c21a790194ec252c281dc404"></a>
|
||||
<h2 class="memtitle"><span class="permalink"><a href="#a557b8031c21a790194ec252c281dc404">◆ </a></span>CIRMM</h2>
|
||||
|
||||
<div class="memitem">
|
||||
<div class="memproto">
|
||||
<table class="memname">
|
||||
<tr>
|
||||
<td class="memname">#define CIRMM   314</td>
|
||||
</tr>
|
||||
</table>
|
||||
</div><div class="memdoc">
|
||||
|
||||
</div>
|
||||
</div>
|
||||
<a id="ad8f1771d4051eafad228df4d397d7e47"></a>
|
||||
<h2 class="memtitle"><span class="permalink"><a href="#ad8f1771d4051eafad228df4d397d7e47">◆ </a></span>CPR</h2>
|
||||
|
||||
<div class="memitem">
|
||||
<div class="memproto">
|
||||
<table class="memname">
|
||||
<tr>
|
||||
<td class="memname">#define CPR   24</td>
|
||||
</tr>
|
||||
</table>
|
||||
</div><div class="memdoc">
|
||||
|
||||
</div>
|
||||
</div>
|
||||
<a id="aa8f0efe0d1ee33354f41f8898d0ee8dd"></a>
|
||||
<h2 class="memtitle"><span class="permalink"><a href="#aa8f0efe0d1ee33354f41f8898d0ee8dd">◆ </a></span>debug</h2>
|
||||
|
||||
<div class="memitem">
|
||||
<div class="memproto">
|
||||
<table class="memname">
|
||||
<tr>
|
||||
<td class="memname">#define debug</td>
|
||||
<td>(</td>
|
||||
<td class="paramname"></td><td>)</td>
|
||||
<td>   {}</td>
|
||||
</tr>
|
||||
</table>
|
||||
</div><div class="memdoc">
|
||||
|
||||
</div>
|
||||
</div>
|
||||
<a id="a4ba93a34cdd9c7b4d1f72021b449906e"></a>
|
||||
<h2 class="memtitle"><span class="permalink"><a href="#a4ba93a34cdd9c7b4d1f72021b449906e">◆ </a></span>DIR_ADVANCE</h2>
|
||||
|
||||
<div class="memitem">
|
||||
<div class="memproto">
|
||||
<table class="memname">
|
||||
<tr>
|
||||
<td class="memname">#define DIR_ADVANCE   HIGH</td>
|
||||
</tr>
|
||||
</table>
|
||||
</div><div class="memdoc">
|
||||
|
||||
</div>
|
||||
</div>
|
||||
<a id="ad52f8b2bf56da6fe72ca2bf9da935ee7"></a>
|
||||
<h2 class="memtitle"><span class="permalink"><a href="#ad52f8b2bf56da6fe72ca2bf9da935ee7">◆ </a></span>DIR_BACKOFF</h2>
|
||||
|
||||
<div class="memitem">
|
||||
<div class="memproto">
|
||||
<table class="memname">
|
||||
<tr>
|
||||
<td class="memname">#define DIR_BACKOFF   LOW</td>
|
||||
</tr>
|
||||
</table>
|
||||
</div><div class="memdoc">
|
||||
|
||||
</div>
|
||||
</div>
|
||||
<a id="a37aea0c86f1a366a15e54142dbcd0f45"></a>
|
||||
<h2 class="memtitle"><span class="permalink"><a href="#a37aea0c86f1a366a15e54142dbcd0f45">◆ </a></span>DIR_INVERSE</h2>
|
||||
|
||||
<div class="memitem">
|
||||
<div class="memproto">
|
||||
<table class="memname">
|
||||
<tr>
|
||||
<td class="memname">#define DIR_INVERSE   !</td>
|
||||
</tr>
|
||||
</table>
|
||||
</div><div class="memdoc">
|
||||
|
||||
</div>
|
||||
</div>
|
||||
<a id="a9812ffc02e34cfd1b5809ba2811a98ae"></a>
|
||||
<h2 class="memtitle"><span class="permalink"><a href="#a9812ffc02e34cfd1b5809ba2811a98ae">◆ </a></span>irqISR</h2>
|
||||
|
||||
<div class="memitem">
|
||||
<div class="memproto">
|
||||
<table class="memname">
|
||||
<tr>
|
||||
<td class="memname">#define irqISR</td>
|
||||
<td>(</td>
|
||||
<td class="paramtype"> </td>
|
||||
<td class="paramname">y, </td>
|
||||
</tr>
|
||||
<tr>
|
||||
<td class="paramkey"></td>
|
||||
<td></td>
|
||||
<td class="paramtype"> </td>
|
||||
<td class="paramname">x </td>
|
||||
</tr>
|
||||
<tr>
|
||||
<td></td>
|
||||
<td>)</td>
|
||||
<td></td><td></td>
|
||||
</tr>
|
||||
</table>
|
||||
</div><div class="memdoc">
|
||||
<b>Value:</b><div class="fragment"><div class="line"> <span class="keywordtype">void</span> x(); \</div>
|
||||
<div class="line"> struct <a class="code" href="structISRVars.html">ISRVars</a> y={x}; \</div>
|
||||
<div class="line"> void x() { \</div>
|
||||
<div class="line"> static <span class="keywordtype">bool</span> first_pulse=<span class="keyword">true</span>; \</div>
|
||||
<div class="line"> y.<a class="code" href="structISRVars.html#a935b7a7cfe9c5a33902ce56256980846">pulseEndMicros</a>=micros(); \</div>
|
||||
<div class="line"> if(first_pulse==<span class="keyword">false</span> && y.pulseEndMicros>y.pulseStartMicros) { \</div>
|
||||
<div class="line"> y.speedPPS=<a class="code" href="MotorWheel_8h.html#a81bcea712b48d6bf8f7193e3de40404b">MICROS_PER_SEC</a>/(y.pulseEndMicros-y.pulseStartMicros); \</div>
|
||||
<div class="line"> <span class="comment">/* y.accPPSS=(y.speedPPS-y.lastSpeedPPS)*y.speedPPS; */</span> \</div>
|
||||
<div class="line"> } <span class="keywordflow">else</span> first_pulse=<span class="keyword">false</span>; \</div>
|
||||
<div class="line"> y.pulseStartMicros=y.pulseEndMicros; \</div>
|
||||
<div class="line"> <span class="comment">/* y.lastSpeedPPS=y.speedPPS; */</span> \</div>
|
||||
<div class="line"> if(y.pinIRQB!=<a class="code" href="MotorWheel_8h.html#adf4d6e9fc5cbf047c65ce74b4fa14117">PIN_UNDEFINED</a>) \</div>
|
||||
<div class="line"> y.currDirection=<a class="code" href="MotorWheel_8h.html#a37aea0c86f1a366a15e54142dbcd0f45">DIR_INVERSE</a>(digitalRead(y.pinIRQ)^digitalRead(y.pinIRQB)); \</div>
|
||||
<div class="line"> y.currDirection==<a class="code" href="MotorWheel_8h.html#a4ba93a34cdd9c7b4d1f72021b449906e">DIR_ADVANCE</a>?++y.pulses:--y.pulses; \</div>
|
||||
<div class="line"> }</div>
|
||||
<div class="ttc" id="aMotorWheel_8h_html_a37aea0c86f1a366a15e54142dbcd0f45"><div class="ttname"><a href="MotorWheel_8h.html#a37aea0c86f1a366a15e54142dbcd0f45">DIR_INVERSE</a></div><div class="ttdeci">#define DIR_INVERSE</div><div class="ttdef"><b>Definition:</b> MotorWheel.h:76</div></div>
|
||||
<div class="ttc" id="aMotorWheel_8h_html_a4ba93a34cdd9c7b4d1f72021b449906e"><div class="ttname"><a href="MotorWheel_8h.html#a4ba93a34cdd9c7b4d1f72021b449906e">DIR_ADVANCE</a></div><div class="ttdeci">#define DIR_ADVANCE</div><div class="ttdef"><b>Definition:</b> MotorWheel.h:53</div></div>
|
||||
<div class="ttc" id="aMotorWheel_8h_html_a81bcea712b48d6bf8f7193e3de40404b"><div class="ttname"><a href="MotorWheel_8h.html#a81bcea712b48d6bf8f7193e3de40404b">MICROS_PER_SEC</a></div><div class="ttdeci">#define MICROS_PER_SEC</div><div class="ttdef"><b>Definition:</b> MotorWheel.h:86</div></div>
|
||||
<div class="ttc" id="aMotorWheel_8h_html_adf4d6e9fc5cbf047c65ce74b4fa14117"><div class="ttname"><a href="MotorWheel_8h.html#adf4d6e9fc5cbf047c65ce74b4fa14117">PIN_UNDEFINED</a></div><div class="ttdeci">#define PIN_UNDEFINED</div><div class="ttdef"><b>Definition:</b> MotorWheel.h:56</div></div>
|
||||
<div class="ttc" id="astructISRVars_html"><div class="ttname"><a href="structISRVars.html">ISRVars</a></div><div class="ttdef"><b>Definition:</b> MotorWheel.h:131</div></div>
|
||||
<div class="ttc" id="astructISRVars_html_a935b7a7cfe9c5a33902ce56256980846"><div class="ttname"><a href="structISRVars.html#a935b7a7cfe9c5a33902ce56256980846">ISRVars::pulseEndMicros</a></div><div class="ttdeci">volatile unsigned long pulseEndMicros</div><div class="ttdef"><b>Definition:</b> MotorWheel.h:136</div></div>
|
||||
</div><!-- fragment -->
|
||||
</div>
|
||||
</div>
|
||||
<a id="a73764abcca0b8bbf6bf355d9f1bab0b9"></a>
|
||||
<h2 class="memtitle"><span class="permalink"><a href="#a73764abcca0b8bbf6bf355d9f1bab0b9">◆ </a></span>KC</h2>
|
||||
|
||||
<div class="memitem">
|
||||
<div class="memproto">
|
||||
<table class="memname">
|
||||
<tr>
|
||||
<td class="memname">#define KC   0.31</td>
|
||||
</tr>
|
||||
</table>
|
||||
</div><div class="memdoc">
|
||||
|
||||
</div>
|
||||
</div>
|
||||
<a id="a1df990f1a1fc97b95e8d53f719968026"></a>
|
||||
<h2 class="memtitle"><span class="permalink"><a href="#a1df990f1a1fc97b95e8d53f719968026">◆ </a></span>MAX_PWM</h2>
|
||||
|
||||
<div class="memitem">
|
||||
<div class="memproto">
|
||||
<table class="memname">
|
||||
<tr>
|
||||
<td class="memname">#define MAX_PWM   255</td>
|
||||
</tr>
|
||||
</table>
|
||||
</div><div class="memdoc">
|
||||
|
||||
</div>
|
||||
</div>
|
||||
<a id="a81d84c8ab20039cad6024ab239ee4086"></a>
|
||||
<h2 class="memtitle"><span class="permalink"><a href="#a81d84c8ab20039cad6024ab239ee4086">◆ </a></span>MAX_SPEEDRPM</h2>
|
||||
|
||||
<div class="memitem">
|
||||
<div class="memproto">
|
||||
<table class="memname">
|
||||
<tr>
|
||||
<td class="memname">#define MAX_SPEEDRPM   8000</td>
|
||||
</tr>
|
||||
</table>
|
||||
</div><div class="memdoc">
|
||||
|
||||
</div>
|
||||
</div>
|
||||
<a id="a81bcea712b48d6bf8f7193e3de40404b"></a>
|
||||
<h2 class="memtitle"><span class="permalink"><a href="#a81bcea712b48d6bf8f7193e3de40404b">◆ </a></span>MICROS_PER_SEC</h2>
|
||||
|
||||
<div class="memitem">
|
||||
<div class="memproto">
|
||||
<table class="memname">
|
||||
<tr>
|
||||
<td class="memname">#define MICROS_PER_SEC   1000000</td>
|
||||
</tr>
|
||||
</table>
|
||||
</div><div class="memdoc">
|
||||
|
||||
</div>
|
||||
</div>
|
||||
<a id="a598a3330b3c21701223ee0ca14316eca"></a>
|
||||
<h2 class="memtitle"><span class="permalink"><a href="#a598a3330b3c21701223ee0ca14316eca">◆ </a></span>PI</h2>
|
||||
|
||||
<div class="memitem">
|
||||
<div class="memproto">
|
||||
<table class="memname">
|
||||
<tr>
|
||||
<td class="memname">#define PI   3.1416</td>
|
||||
</tr>
|
||||
</table>
|
||||
</div><div class="memdoc">
|
||||
|
||||
</div>
|
||||
</div>
|
||||
<a id="adf4d6e9fc5cbf047c65ce74b4fa14117"></a>
|
||||
<h2 class="memtitle"><span class="permalink"><a href="#adf4d6e9fc5cbf047c65ce74b4fa14117">◆ </a></span>PIN_UNDEFINED</h2>
|
||||
|
||||
<div class="memitem">
|
||||
<div class="memproto">
|
||||
<table class="memname">
|
||||
<tr>
|
||||
<td class="memname">#define PIN_UNDEFINED   255</td>
|
||||
</tr>
|
||||
</table>
|
||||
</div><div class="memdoc">
|
||||
|
||||
</div>
|
||||
</div>
|
||||
<a id="a545c3d33941dafc6ffd8cd9a61f6fca4"></a>
|
||||
<h2 class="memtitle"><span class="permalink"><a href="#a545c3d33941dafc6ffd8cd9a61f6fca4">◆ </a></span>REDUCTION_RATIO</h2>
|
||||
|
||||
<div class="memitem">
|
||||
<div class="memproto">
|
||||
<table class="memname">
|
||||
<tr>
|
||||
<td class="memname">#define REDUCTION_RATIO   64</td>
|
||||
</tr>
|
||||
</table>
|
||||
</div><div class="memdoc">
|
||||
|
||||
</div>
|
||||
</div>
|
||||
<a id="a2d979268f4539332ee9b1abc5b58e974"></a>
|
||||
<h2 class="memtitle"><span class="permalink"><a href="#a2d979268f4539332ee9b1abc5b58e974">◆ </a></span>REF_VOLT</h2>
|
||||
|
||||
<div class="memitem">
|
||||
<div class="memproto">
|
||||
<table class="memname">
|
||||
<tr>
|
||||
<td class="memname">#define REF_VOLT   12</td>
|
||||
</tr>
|
||||
</table>
|
||||
</div><div class="memdoc">
|
||||
|
||||
</div>
|
||||
</div>
|
||||
<a id="a755b9528bf80376f0476829e8078a0da"></a>
|
||||
<h2 class="memtitle"><span class="permalink"><a href="#a755b9528bf80376f0476829e8078a0da">◆ </a></span>SAMPLETIME</h2>
|
||||
|
||||
<div class="memitem">
|
||||
<div class="memproto">
|
||||
<table class="memname">
|
||||
<tr>
|
||||
<td class="memname">#define SAMPLETIME   5</td>
|
||||
</tr>
|
||||
</table>
|
||||
</div><div class="memdoc">
|
||||
|
||||
</div>
|
||||
</div>
|
||||
<a id="ac47b302f1b8d2a7a9c035c417247be76"></a>
|
||||
<h2 class="memtitle"><span class="permalink"><a href="#ac47b302f1b8d2a7a9c035c417247be76">◆ </a></span>SEC_PER_MIN</h2>
|
||||
|
||||
<div class="memitem">
|
||||
<div class="memproto">
|
||||
<table class="memname">
|
||||
<tr>
|
||||
<td class="memname">#define SEC_PER_MIN   60</td>
|
||||
</tr>
|
||||
</table>
|
||||
</div><div class="memdoc">
|
||||
|
||||
</div>
|
||||
</div>
|
||||
<a id="a2ab9b66762dd6eb975292a7e83116bec"></a>
|
||||
<h2 class="memtitle"><span class="permalink"><a href="#a2ab9b66762dd6eb975292a7e83116bec">◆ </a></span>SPEEDPPS2SPEEDRPM</h2>
|
||||
|
||||
<div class="memitem">
|
||||
<div class="memproto">
|
||||
<table class="memname">
|
||||
<tr>
|
||||
<td class="memname">#define SPEEDPPS2SPEEDRPM</td>
|
||||
<td>(</td>
|
||||
<td class="paramtype"> </td>
|
||||
<td class="paramname">freq</td><td>)</td>
|
||||
<td>   ((unsigned long)(freq)*(<a class="el" href="MotorWheel_8h.html#ac47b302f1b8d2a7a9c035c417247be76">SEC_PER_MIN</a>)/(<a class="el" href="MotorWheel_8h.html#ad8f1771d4051eafad228df4d397d7e47">CPR</a>))</td>
|
||||
</tr>
|
||||
</table>
|
||||
</div><div class="memdoc">
|
||||
|
||||
</div>
|
||||
</div>
|
||||
<a id="a75450bf317fb4edd6c44dbe6b2ff7673"></a>
|
||||
<h2 class="memtitle"><span class="permalink"><a href="#a75450bf317fb4edd6c44dbe6b2ff7673">◆ </a></span>TAUD</h2>
|
||||
|
||||
<div class="memitem">
|
||||
<div class="memproto">
|
||||
<table class="memname">
|
||||
<tr>
|
||||
<td class="memname">#define TAUD   0.00</td>
|
||||
</tr>
|
||||
</table>
|
||||
</div><div class="memdoc">
|
||||
|
||||
</div>
|
||||
</div>
|
||||
<a id="a73c066690ee81cb3f9c801205a237acd"></a>
|
||||
<h2 class="memtitle"><span class="permalink"><a href="#a73c066690ee81cb3f9c801205a237acd">◆ </a></span>TAUI</h2>
|
||||
|
||||
<div class="memitem">
|
||||
<div class="memproto">
|
||||
<table class="memname">
|
||||
<tr>
|
||||
<td class="memname">#define TAUI   0.02</td>
|
||||
</tr>
|
||||
</table>
|
||||
</div><div class="memdoc">
|
||||
|
||||
</div>
|
||||
</div>
|
||||
<a id="a86de85f5177dabb5ff712bf180db43aa"></a>
|
||||
<h2 class="memtitle"><span class="permalink"><a href="#a86de85f5177dabb5ff712bf180db43aa">◆ </a></span>TRIGGER</h2>
|
||||
|
||||
<div class="memitem">
|
||||
<div class="memproto">
|
||||
<table class="memname">
|
||||
<tr>
|
||||
<td class="memname">#define TRIGGER   CHANGE</td>
|
||||
</tr>
|
||||
</table>
|
||||
</div><div class="memdoc">
|
||||
|
||||
</div>
|
||||
</div>
|
||||
</div><!-- contents -->
|
||||
<!-- start footer part -->
|
||||
<hr class="footer"/><address class="footer"><small>
|
||||
Generated by <a href="https://www.doxygen.org/index.html"><img class="footer" src="doxygen.svg" width="104" height="31" alt="doxygen"/></a> 1.9.1
|
||||
</small></address>
|
||||
</body>
|
||||
</html>
|
@ -1,7 +0,0 @@
|
||||
<map id="lib/MotorWheel/MotorWheel.h" name="lib/MotorWheel/MotorWheel.h">
|
||||
<area shape="rect" id="node1" title=" " alt="" coords="397,5,613,32"/>
|
||||
<area shape="rect" id="node2" href="$UARTCom_8cpp.html" title=" " alt="" coords="5,80,248,107"/>
|
||||
<area shape="rect" id="node3" href="$UCommands_8cpp.html" title=" " alt="" coords="272,80,533,107"/>
|
||||
<area shape="rect" id="node4" href="$main_8cpp.html" title=" " alt="" coords="557,80,662,107"/>
|
||||
<area shape="rect" id="node5" href="$MotorWheel_8cpp.html" title=" " alt="" coords="686,80,917,107"/>
|
||||
</map>
|
@ -1 +0,0 @@
|
||||
c034deeaba962af687fc3c804a0de12e
|
Before Width: | Height: | Size: 9.9 KiB |
@ -1,8 +0,0 @@
|
||||
<map id="lib/MotorWheel/MotorWheel.h" name="lib/MotorWheel/MotorWheel.h">
|
||||
<area shape="rect" id="node1" title=" " alt="" coords="38,5,254,32"/>
|
||||
<area shape="rect" id="node2" href="$PID__Beta6_8h.html" title=" " alt="" coords="29,80,130,107"/>
|
||||
<area shape="rect" id="node3" href="$PinChangeInt_8h.html" title=" " alt="" coords="154,80,274,107"/>
|
||||
<area shape="rect" id="node4" title=" " alt="" coords="5,155,108,181"/>
|
||||
<area shape="rect" id="node5" href="$PinChangeIntConfig_8h.html" title=" " alt="" coords="133,155,295,181"/>
|
||||
<area shape="rect" id="node6" title=" " alt="" coords="319,155,437,181"/>
|
||||
</map>
|
@ -1 +0,0 @@
|
||||
30824c8b153c7d99bc245a493724c9d7
|
Before Width: | Height: | Size: 12 KiB |
@ -1,494 +0,0 @@
|
||||
<!DOCTYPE html PUBLIC "-//W3C//DTD XHTML 1.0 Transitional//EN" "https://www.w3.org/TR/xhtml1/DTD/xhtml1-transitional.dtd">
|
||||
<html xmlns="http://www.w3.org/1999/xhtml">
|
||||
<head>
|
||||
<meta http-equiv="Content-Type" content="text/xhtml;charset=UTF-8"/>
|
||||
<meta http-equiv="X-UA-Compatible" content="IE=9"/>
|
||||
<meta name="generator" content="Doxygen 1.9.1"/>
|
||||
<meta name="viewport" content="width=device-width, initial-scale=1"/>
|
||||
<title>DCAITI Robot Hardware: lib/MotorWheel/MotorWheel.h Source File</title>
|
||||
<link href="tabs.css" rel="stylesheet" type="text/css"/>
|
||||
<script type="text/javascript" src="jquery.js"></script>
|
||||
<script type="text/javascript" src="dynsections.js"></script>
|
||||
<link href="search/search.css" rel="stylesheet" type="text/css"/>
|
||||
<script type="text/javascript" src="search/searchdata.js"></script>
|
||||
<script type="text/javascript" src="search/search.js"></script>
|
||||
<link href="doxygen.css" rel="stylesheet" type="text/css" />
|
||||
</head>
|
||||
<body>
|
||||
<div id="top"><!-- do not remove this div, it is closed by doxygen! -->
|
||||
<div id="titlearea">
|
||||
<table cellspacing="0" cellpadding="0">
|
||||
<tbody>
|
||||
<tr style="height: 56px;">
|
||||
<td id="projectalign" style="padding-left: 0.5em;">
|
||||
<div id="projectname">DCAITI Robot Hardware
|
||||
 <span id="projectnumber">1.0</span>
|
||||
</div>
|
||||
</td>
|
||||
</tr>
|
||||
</tbody>
|
||||
</table>
|
||||
</div>
|
||||
<!-- end header part -->
|
||||
<!-- Generated by Doxygen 1.9.1 -->
|
||||
<script type="text/javascript">
|
||||
/* @license magnet:?xt=urn:btih:cf05388f2679ee054f2beb29a391d25f4e673ac3&dn=gpl-2.0.txt GPL-v2 */
|
||||
var searchBox = new SearchBox("searchBox", "search",false,'Search','.html');
|
||||
/* @license-end */
|
||||
</script>
|
||||
<script type="text/javascript" src="menudata.js"></script>
|
||||
<script type="text/javascript" src="menu.js"></script>
|
||||
<script type="text/javascript">
|
||||
/* @license magnet:?xt=urn:btih:cf05388f2679ee054f2beb29a391d25f4e673ac3&dn=gpl-2.0.txt GPL-v2 */
|
||||
$(function() {
|
||||
initMenu('',true,false,'search.php','Search');
|
||||
$(document).ready(function() { init_search(); });
|
||||
});
|
||||
/* @license-end */</script>
|
||||
<div id="main-nav"></div>
|
||||
<!-- window showing the filter options -->
|
||||
<div id="MSearchSelectWindow"
|
||||
onmouseover="return searchBox.OnSearchSelectShow()"
|
||||
onmouseout="return searchBox.OnSearchSelectHide()"
|
||||
onkeydown="return searchBox.OnSearchSelectKey(event)">
|
||||
</div>
|
||||
|
||||
<!-- iframe showing the search results (closed by default) -->
|
||||
<div id="MSearchResultsWindow">
|
||||
<iframe src="javascript:void(0)" frameborder="0"
|
||||
name="MSearchResults" id="MSearchResults">
|
||||
</iframe>
|
||||
</div>
|
||||
|
||||
<div id="nav-path" class="navpath">
|
||||
<ul>
|
||||
<li class="navelem"><a class="el" href="dir_97aefd0d527b934f1d99a682da8fe6a9.html">lib</a></li><li class="navelem"><a class="el" href="dir_10c6c21535d653b7c685bbf5a23d61f7.html">MotorWheel</a></li> </ul>
|
||||
</div>
|
||||
</div><!-- top -->
|
||||
<div class="header">
|
||||
<div class="headertitle">
|
||||
<div class="title">MotorWheel.h</div> </div>
|
||||
</div><!--header-->
|
||||
<div class="contents">
|
||||
<a href="MotorWheel_8h.html">Go to the documentation of this file.</a><div class="fragment"><div class="line"><a name="l00001"></a><span class="lineno"> 1</span>  </div>
|
||||
<div class="line"><a name="l00002"></a><span class="lineno"> 2</span> <span class="comment">/*</span></div>
|
||||
<div class="line"><a name="l00003"></a><span class="lineno"> 3</span> <span class="comment">V1.1 201104</span></div>
|
||||
<div class="line"><a name="l00004"></a><span class="lineno"> 4</span> <span class="comment">1. motorwheel library version 1.1,compatible with maple.</span></div>
|
||||
<div class="line"><a name="l00005"></a><span class="lineno"> 5</span> <span class="comment"></span> </div>
|
||||
<div class="line"><a name="l00006"></a><span class="lineno"> 6</span> <span class="comment">V1.1.1 201110</span></div>
|
||||
<div class="line"><a name="l00007"></a><span class="lineno"> 7</span> <span class="comment">1. Add Acceleration</span></div>
|
||||
<div class="line"><a name="l00008"></a><span class="lineno"> 8</span> <span class="comment"></span> </div>
|
||||
<div class="line"><a name="l00009"></a><span class="lineno"> 9</span> <span class="comment">V1.2 201207</span></div>
|
||||
<div class="line"><a name="l00010"></a><span class="lineno"> 10</span> <span class="comment">1. Double CPR from 12 to 24, Interrupt Type from RISING to CHANGE.</span></div>
|
||||
<div class="line"><a name="l00011"></a><span class="lineno"> 11</span> <span class="comment">2. Reduce default sample time from 10ms to 5ms.</span></div>
|
||||
<div class="line"><a name="l00012"></a><span class="lineno"> 12</span> <span class="comment">3. Compatible with Namiki 22CL-3501PG80:1, by "#define _NAMIKI_MOTOR" before "#include ...".</span></div>
|
||||
<div class="line"><a name="l00013"></a><span class="lineno"> 13</span> <span class="comment"></span> </div>
|
||||
<div class="line"><a name="l00014"></a><span class="lineno"> 14</span> <span class="comment">V1.3 201209</span></div>
|
||||
<div class="line"><a name="l00015"></a><span class="lineno"> 15</span> <span class="comment">1. R2WD::delayMS(), Omni3WD::delayMS(), Omni4WD::delayMS() are re-implemented, more exactly.</span></div>
|
||||
<div class="line"><a name="l00016"></a><span class="lineno"> 16</span> <span class="comment">2. getSpeedRPM(), setSpeedRPM(), getSpeedMMPS(), setSpeedMMPS() are plug-minus/direction sensitive now.</span></div>
|
||||
<div class="line"><a name="l00017"></a><span class="lineno"> 17</span> <span class="comment">3. Acceleration is disabled.</span></div>
|
||||
<div class="line"><a name="l00018"></a><span class="lineno"> 18</span> <span class="comment"></span> </div>
|
||||
<div class="line"><a name="l00019"></a><span class="lineno"> 19</span> <span class="comment">V1.4 201209 Not Released</span></div>
|
||||
<div class="line"><a name="l00020"></a><span class="lineno"> 20</span> <span class="comment">1. Increase CPR from 24 to 48 for Faulhaber 2342.</span></div>
|
||||
<div class="line"><a name="l00021"></a><span class="lineno"> 21</span> <span class="comment"></span> </div>
|
||||
<div class="line"><a name="l00022"></a><span class="lineno"> 22</span> <span class="comment">V1.5 201209 Omni4WD is re-implemented, and now return value of Omni4WD::getSpeedMMPS() is correct.</span></div>
|
||||
<div class="line"><a name="l00023"></a><span class="lineno"> 23</span> <span class="comment"></span> </div>
|
||||
<div class="line"><a name="l00024"></a><span class="lineno"> 24</span> <span class="comment"> */</span></div>
|
||||
<div class="line"><a name="l00025"></a><span class="lineno"> 25</span>  </div>
|
||||
<div class="line"><a name="l00026"></a><span class="lineno"> 26</span> <span class="comment">/*for maple*/</span></div>
|
||||
<div class="line"><a name="l00027"></a><span class="lineno"> 27</span> <span class="preprocessor">#if defined(BOARD_maple) || defined(BOARD_maple_native) || defined(BOARD_maple_mini)</span></div>
|
||||
<div class="line"><a name="l00028"></a><span class="lineno"> 28</span> <span class="preprocessor"> #include "wirish.h"</span> </div>
|
||||
<div class="line"><a name="l00029"></a><span class="lineno"> 29</span> <span class="preprocessor"> #include "./../PID_Beta6/PID_Beta6.h"</span></div>
|
||||
<div class="line"><a name="l00030"></a><span class="lineno"> 30</span> <span class="preprocessor"> #include "ext_interrupts.h"</span></div>
|
||||
<div class="line"><a name="l00031"></a><span class="lineno"> 31</span>  </div>
|
||||
<div class="line"><a name="l00032"></a><span class="lineno"> 32</span> <span class="comment">/*for arduino*/</span> </div>
|
||||
<div class="line"><a name="l00033"></a><span class="lineno"> 33</span> <span class="preprocessor">#else</span></div>
|
||||
<div class="line"><a name="l00034"></a><span class="lineno"> 34</span>  <span class="comment">//#include<Arduino.h></span></div>
|
||||
<div class="line"><a name="l00035"></a><span class="lineno"> 35</span>  <span class="comment">//#include<WProgram.h></span></div>
|
||||
<div class="line"><a name="l00036"></a><span class="lineno"> 36</span> <span class="preprocessor"> #include<<a class="code" href="PID__Beta6_8h.html">PID_Beta6.h</a>></span></div>
|
||||
<div class="line"><a name="l00037"></a><span class="lineno"> 37</span> <span class="preprocessor"> #include<<a class="code" href="PinChangeInt_8h.html">PinChangeInt.h</a>></span></div>
|
||||
<div class="line"><a name="l00038"></a><span class="lineno"> 38</span>  </div>
|
||||
<div class="line"><a name="l00039"></a><span class="lineno"> 39</span> <span class="preprocessor">#endif</span></div>
|
||||
<div class="line"><a name="l00040"></a><span class="lineno"> 40</span>  </div>
|
||||
<div class="line"><a name="l00041"></a><span class="lineno"> 41</span> <span class="comment">/*</span></div>
|
||||
<div class="line"><a name="l00042"></a><span class="lineno"> 42</span> <span class="comment"></span> </div>
|
||||
<div class="line"><a name="l00043"></a><span class="lineno"> 43</span> <span class="comment"> class PID</span></div>
|
||||
<div class="line"><a name="l00044"></a><span class="lineno"> 44</span> <span class="comment"> class Motor</span></div>
|
||||
<div class="line"><a name="l00045"></a><span class="lineno"> 45</span> <span class="comment"> class GearedMotor</span></div>
|
||||
<div class="line"><a name="l00046"></a><span class="lineno"> 46</span> <span class="comment"> class MotorWheel</span></div>
|
||||
<div class="line"><a name="l00047"></a><span class="lineno"> 47</span> <span class="comment"></span> </div>
|
||||
<div class="line"><a name="l00048"></a><span class="lineno"> 48</span> <span class="comment"> */</span></div>
|
||||
<div class="line"><a name="l00049"></a><span class="lineno"> 49</span>  </div>
|
||||
<div class="line"><a name="l00050"></a><span class="lineno"> 50</span> <span class="preprocessor">#ifndef MotorWheel_H</span></div>
|
||||
<div class="line"><a name="l00051"></a><span class="lineno"> 51</span> <span class="preprocessor">#define MotorWheel_H</span></div>
|
||||
<div class="line"><a name="l00052"></a><span class="lineno"> 52</span>  </div>
|
||||
<div class="line"><a name="l00053"></a><span class="lineno"><a class="line" href="MotorWheel_8h.html#a4ba93a34cdd9c7b4d1f72021b449906e"> 53</a></span> <span class="preprocessor">#define DIR_ADVANCE HIGH</span></div>
|
||||
<div class="line"><a name="l00054"></a><span class="lineno"><a class="line" href="MotorWheel_8h.html#ad52f8b2bf56da6fe72ca2bf9da935ee7"> 54</a></span> <span class="preprocessor">#define DIR_BACKOFF LOW</span></div>
|
||||
<div class="line"><a name="l00055"></a><span class="lineno"> 55</span>  </div>
|
||||
<div class="line"><a name="l00056"></a><span class="lineno"><a class="line" href="MotorWheel_8h.html#adf4d6e9fc5cbf047c65ce74b4fa14117"> 56</a></span> <span class="preprocessor">#define PIN_UNDEFINED 255</span></div>
|
||||
<div class="line"><a name="l00057"></a><span class="lineno"><a class="line" href="MotorWheel_8h.html#a2d979268f4539332ee9b1abc5b58e974"> 57</a></span> <span class="preprocessor">#define REF_VOLT 12</span></div>
|
||||
<div class="line"><a name="l00058"></a><span class="lineno"> 58</span> <span class="comment">/*for maple*/</span></div>
|
||||
<div class="line"><a name="l00059"></a><span class="lineno"> 59</span> <span class="preprocessor">#if defined(BOARD_maple) || defined(BOARD_maple_native) || defined(BOARD_maple_mini)</span></div>
|
||||
<div class="line"><a name="l00060"></a><span class="lineno"> 60</span> <span class="preprocessor"> #define MAX_PWM 3599</span></div>
|
||||
<div class="line"><a name="l00061"></a><span class="lineno"> 61</span>  </div>
|
||||
<div class="line"><a name="l00062"></a><span class="lineno"> 62</span> <span class="comment">/*for arduino*/</span> </div>
|
||||
<div class="line"><a name="l00063"></a><span class="lineno"> 63</span> <span class="preprocessor">#else</span></div>
|
||||
<div class="line"><a name="l00064"></a><span class="lineno"><a class="line" href="MotorWheel_8h.html#a1df990f1a1fc97b95e8d53f719968026"> 64</a></span> <span class="preprocessor"> #define MAX_PWM 255</span></div>
|
||||
<div class="line"><a name="l00065"></a><span class="lineno"> 65</span>  </div>
|
||||
<div class="line"><a name="l00066"></a><span class="lineno"> 66</span> <span class="preprocessor">#endif</span></div>
|
||||
<div class="line"><a name="l00067"></a><span class="lineno"> 67</span>  </div>
|
||||
<div class="line"><a name="l00068"></a><span class="lineno"> 68</span> <span class="preprocessor">#ifdef _NAMIKI_MOTOR</span></div>
|
||||
<div class="line"><a name="l00069"></a><span class="lineno"> 69</span> <span class="preprocessor"> #define TRIGGER CHANGE</span></div>
|
||||
<div class="line"><a name="l00070"></a><span class="lineno"> 70</span> <span class="preprocessor"> #define CPR 4 </span><span class="comment">// Namiki motor</span></div>
|
||||
<div class="line"><a name="l00071"></a><span class="lineno"> 71</span> <span class="preprocessor"> #define DIR_INVERSE</span></div>
|
||||
<div class="line"><a name="l00072"></a><span class="lineno"> 72</span> <span class="preprocessor"> #define REDUCTION_RATIO 80</span></div>
|
||||
<div class="line"><a name="l00073"></a><span class="lineno"> 73</span> <span class="preprocessor">#else</span></div>
|
||||
<div class="line"><a name="l00074"></a><span class="lineno"><a class="line" href="MotorWheel_8h.html#a86de85f5177dabb5ff712bf180db43aa"> 74</a></span> <span class="preprocessor"> #define TRIGGER CHANGE</span></div>
|
||||
<div class="line"><a name="l00075"></a><span class="lineno"><a class="line" href="MotorWheel_8h.html#ad8f1771d4051eafad228df4d397d7e47"> 75</a></span> <span class="preprocessor"> #define CPR 24 </span><span class="comment">// Faulhaber motor</span></div>
|
||||
<div class="line"><a name="l00076"></a><span class="lineno"><a class="line" href="MotorWheel_8h.html#a37aea0c86f1a366a15e54142dbcd0f45"> 76</a></span> <span class="preprocessor"> #define DIR_INVERSE !</span></div>
|
||||
<div class="line"><a name="l00077"></a><span class="lineno"><a class="line" href="MotorWheel_8h.html#a545c3d33941dafc6ffd8cd9a61f6fca4"> 77</a></span> <span class="preprocessor"> #define REDUCTION_RATIO 64</span></div>
|
||||
<div class="line"><a name="l00078"></a><span class="lineno"> 78</span> <span class="preprocessor">#endif</span></div>
|
||||
<div class="line"><a name="l00079"></a><span class="lineno"> 79</span>  </div>
|
||||
<div class="line"><a name="l00080"></a><span class="lineno"><a class="line" href="MotorWheel_8h.html#a81d84c8ab20039cad6024ab239ee4086"> 80</a></span> <span class="preprocessor">#define MAX_SPEEDRPM 8000</span></div>
|
||||
<div class="line"><a name="l00081"></a><span class="lineno"> 81</span> <span class="comment">//#define DESIRED_SPEEDRPM 3000</span></div>
|
||||
<div class="line"><a name="l00082"></a><span class="lineno"> 82</span> <span class="comment">//#define SPEED_CONSTANT_RPM 713</span></div>
|
||||
<div class="line"><a name="l00083"></a><span class="lineno"> 83</span> <span class="comment">//#define PWM2SPEED_RESOLUTION 143 //713 * 0.2</span></div>
|
||||
<div class="line"><a name="l00084"></a><span class="lineno"> 84</span>  </div>
|
||||
<div class="line"><a name="l00085"></a><span class="lineno"><a class="line" href="MotorWheel_8h.html#ac47b302f1b8d2a7a9c035c417247be76"> 85</a></span> <span class="preprocessor">#define SEC_PER_MIN 60</span></div>
|
||||
<div class="line"><a name="l00086"></a><span class="lineno"><a class="line" href="MotorWheel_8h.html#a81bcea712b48d6bf8f7193e3de40404b"> 86</a></span> <span class="preprocessor">#define MICROS_PER_SEC 1000000</span></div>
|
||||
<div class="line"><a name="l00087"></a><span class="lineno"> 87</span> <span class="comment">//#define SPEEDPPS2SPEEDRPM(freq) ((freq)*((SEC_PER_MIN)/(CPR))) //(freq*SEC_PER_MIN/CPR)</span></div>
|
||||
<div class="line"><a name="l00088"></a><span class="lineno"><a class="line" href="MotorWheel_8h.html#a2ab9b66762dd6eb975292a7e83116bec"> 88</a></span> <span class="preprocessor">#define SPEEDPPS2SPEEDRPM(freq) ((unsigned long)(freq)*(SEC_PER_MIN)/(CPR)) </span><span class="comment">//(freq*SEC_PER_MIN/CPR)</span></div>
|
||||
<div class="line"><a name="l00089"></a><span class="lineno"> 89</span> <span class="comment">//#define SPEEDPPS2SPEED2VOLT(spd) ((spd)/SPEED_CONSTANT_RPM)</span></div>
|
||||
<div class="line"><a name="l00090"></a><span class="lineno"> 90</span> <span class="comment">//#define MAX_SPEEDPPS ((MAX_SPEEDRPM*CPR)/SEC_PER_MIN)</span></div>
|
||||
<div class="line"><a name="l00091"></a><span class="lineno"> 91</span> <span class="comment">//#define MIN_SPEEDPPS 0</span></div>
|
||||
<div class="line"><a name="l00092"></a><span class="lineno"> 92</span>  </div>
|
||||
<div class="line"><a name="l00093"></a><span class="lineno"><a class="line" href="MotorWheel_8h.html#a73764abcca0b8bbf6bf355d9f1bab0b9"> 93</a></span> <span class="preprocessor">#define KC 0.31</span></div>
|
||||
<div class="line"><a name="l00094"></a><span class="lineno"><a class="line" href="MotorWheel_8h.html#a73c066690ee81cb3f9c801205a237acd"> 94</a></span> <span class="preprocessor">#define TAUI 0.02</span></div>
|
||||
<div class="line"><a name="l00095"></a><span class="lineno"><a class="line" href="MotorWheel_8h.html#a75450bf317fb4edd6c44dbe6b2ff7673"> 95</a></span> <span class="preprocessor">#define TAUD 0.00</span></div>
|
||||
<div class="line"><a name="l00096"></a><span class="lineno"><a class="line" href="MotorWheel_8h.html#a755b9528bf80376f0476829e8078a0da"> 96</a></span> <span class="preprocessor">#define SAMPLETIME 5</span></div>
|
||||
<div class="line"><a name="l00097"></a><span class="lineno"> 97</span>  </div>
|
||||
<div class="line"><a name="l00098"></a><span class="lineno"><a class="line" href="MotorWheel_8h.html#ab201ec4c4f600966de3779313f08d2c3"> 98</a></span> <span class="preprocessor">#define Baudrate 19200</span></div>
|
||||
<div class="line"><a name="l00099"></a><span class="lineno"> 99</span> <span class="comment">/*</span></div>
|
||||
<div class="line"><a name="l00100"></a><span class="lineno"> 100</span> <span class="comment">#ifndef DEBUG</span></div>
|
||||
<div class="line"><a name="l00101"></a><span class="lineno"> 101</span> <span class="comment">#define DEBUG</span></div>
|
||||
<div class="line"><a name="l00102"></a><span class="lineno"> 102</span> <span class="comment">#endif</span></div>
|
||||
<div class="line"><a name="l00103"></a><span class="lineno"> 103</span> <span class="comment"> */</span></div>
|
||||
<div class="line"><a name="l00104"></a><span class="lineno"> 104</span> <span class="preprocessor">#ifdef DEBUG</span></div>
|
||||
<div class="line"><a name="l00105"></a><span class="lineno"> 105</span> <span class="preprocessor">#define debug() { \</span></div>
|
||||
<div class="line"><a name="l00106"></a><span class="lineno"> 106</span> <span class="preprocessor"> if(!Serial.available()) Serial.begin(Baudrate); \</span></div>
|
||||
<div class="line"><a name="l00107"></a><span class="lineno"> 107</span> <span class="preprocessor"> Serial.println(__func__);}</span></div>
|
||||
<div class="line"><a name="l00108"></a><span class="lineno"> 108</span> <span class="preprocessor">#else</span></div>
|
||||
<div class="line"><a name="l00109"></a><span class="lineno"><a class="line" href="MotorWheel_8h.html#aa8f0efe0d1ee33354f41f8898d0ee8dd"> 109</a></span> <span class="preprocessor">#define debug() {}</span></div>
|
||||
<div class="line"><a name="l00110"></a><span class="lineno"> 110</span> <span class="preprocessor">#endif</span></div>
|
||||
<div class="line"><a name="l00111"></a><span class="lineno"> 111</span>  </div>
|
||||
<div class="line"><a name="l00112"></a><span class="lineno"> 112</span>  </div>
|
||||
<div class="line"><a name="l00113"></a><span class="lineno"> 113</span> <span class="comment">// Interrupt Type: RISING --> CHANGE 201207</span></div>
|
||||
<div class="line"><a name="l00114"></a><span class="lineno"><a class="line" href="MotorWheel_8h.html#a9812ffc02e34cfd1b5809ba2811a98ae"> 114</a></span> <span class="preprocessor">#define irqISR(y,x) \</span></div>
|
||||
<div class="line"><a name="l00115"></a><span class="lineno"> 115</span> <span class="preprocessor"> void x(); \</span></div>
|
||||
<div class="line"><a name="l00116"></a><span class="lineno"> 116</span> <span class="preprocessor"> struct ISRVars y={x}; \</span></div>
|
||||
<div class="line"><a name="l00117"></a><span class="lineno"> 117</span> <span class="preprocessor"> void x() { \</span></div>
|
||||
<div class="line"><a name="l00118"></a><span class="lineno"> 118</span> <span class="preprocessor"> static bool first_pulse=true; \</span></div>
|
||||
<div class="line"><a name="l00119"></a><span class="lineno"> 119</span> <span class="preprocessor"> y.pulseEndMicros=micros(); \</span></div>
|
||||
<div class="line"><a name="l00120"></a><span class="lineno"> 120</span> <span class="preprocessor"> if(first_pulse==false && y.pulseEndMicros>y.pulseStartMicros) { \</span></div>
|
||||
<div class="line"><a name="l00121"></a><span class="lineno"> 121</span> <span class="preprocessor"> y.speedPPS=MICROS_PER_SEC/(y.pulseEndMicros-y.pulseStartMicros); \</span></div>
|
||||
<div class="line"><a name="l00122"></a><span class="lineno"> 122</span> <span class="preprocessor"> </span><span class="comment">/* y.accPPSS=(y.speedPPS-y.lastSpeedPPS)*y.speedPPS; */</span><span class="preprocessor"> \</span></div>
|
||||
<div class="line"><a name="l00123"></a><span class="lineno"> 123</span> <span class="preprocessor"> } else first_pulse=false; \</span></div>
|
||||
<div class="line"><a name="l00124"></a><span class="lineno"> 124</span> <span class="preprocessor"> y.pulseStartMicros=y.pulseEndMicros; \</span></div>
|
||||
<div class="line"><a name="l00125"></a><span class="lineno"> 125</span> <span class="preprocessor"> </span><span class="comment">/* y.lastSpeedPPS=y.speedPPS; */</span><span class="preprocessor"> \</span></div>
|
||||
<div class="line"><a name="l00126"></a><span class="lineno"> 126</span> <span class="preprocessor"> if(y.pinIRQB!=PIN_UNDEFINED) \</span></div>
|
||||
<div class="line"><a name="l00127"></a><span class="lineno"> 127</span> <span class="preprocessor"> y.currDirection=DIR_INVERSE(digitalRead(y.pinIRQ)^digitalRead(y.pinIRQB)); \</span></div>
|
||||
<div class="line"><a name="l00128"></a><span class="lineno"> 128</span> <span class="preprocessor"> y.currDirection==DIR_ADVANCE?++y.pulses:--y.pulses; \</span></div>
|
||||
<div class="line"><a name="l00129"></a><span class="lineno"> 129</span> <span class="preprocessor"> } </span></div>
|
||||
<div class="line"><a name="l00130"></a><span class="lineno"> 130</span>  </div>
|
||||
<div class="line"><a name="l00131"></a><span class="lineno"><a class="line" href="structISRVars.html"> 131</a></span> <span class="keyword">struct </span><a class="code" href="structISRVars.html">ISRVars</a> {</div>
|
||||
<div class="line"><a name="l00132"></a><span class="lineno"><a class="line" href="structISRVars.html#a38f71602d525494877c66159cf704309"> 132</a></span>  void (*<a class="code" href="structISRVars.html#a38f71602d525494877c66159cf704309">ISRfunc</a>)();</div>
|
||||
<div class="line"><a name="l00133"></a><span class="lineno"> 133</span>  <span class="comment">//volatile unsigned long pulses;</span></div>
|
||||
<div class="line"><a name="l00134"></a><span class="lineno"><a class="line" href="structISRVars.html#a5fb13f185745e43667ba30d2c0481f74"> 134</a></span>  <span class="keyword">volatile</span> <span class="keywordtype">long</span> <a class="code" href="structISRVars.html#a5fb13f185745e43667ba30d2c0481f74">pulses</a>; <span class="comment">// 201104, direction sensitive</span></div>
|
||||
<div class="line"><a name="l00135"></a><span class="lineno"><a class="line" href="structISRVars.html#aad94840301dc39f51a918b556df8fc11"> 135</a></span>  <span class="keyword">volatile</span> <span class="keywordtype">unsigned</span> <span class="keywordtype">long</span> <a class="code" href="structISRVars.html#aad94840301dc39f51a918b556df8fc11">pulseStartMicros</a>;</div>
|
||||
<div class="line"><a name="l00136"></a><span class="lineno"><a class="line" href="structISRVars.html#a935b7a7cfe9c5a33902ce56256980846"> 136</a></span>  <span class="keyword">volatile</span> <span class="keywordtype">unsigned</span> <span class="keywordtype">long</span> <a class="code" href="structISRVars.html#a935b7a7cfe9c5a33902ce56256980846">pulseEndMicros</a>;</div>
|
||||
<div class="line"><a name="l00137"></a><span class="lineno"><a class="line" href="structISRVars.html#af6857712234eae5709feba7c699e0ac7"> 137</a></span>  <span class="keyword">volatile</span> <span class="keywordtype">unsigned</span> <span class="keywordtype">int</span> <a class="code" href="structISRVars.html#af6857712234eae5709feba7c699e0ac7">speedPPS</a>;</div>
|
||||
<div class="line"><a name="l00138"></a><span class="lineno"> 138</span>  <span class="comment">//volatile unsigned int lastSpeedPPS;</span></div>
|
||||
<div class="line"><a name="l00139"></a><span class="lineno"> 139</span>  <span class="comment">//volatile int accPPSS; // acceleration, Pulse Per Sec^2</span></div>
|
||||
<div class="line"><a name="l00140"></a><span class="lineno"><a class="line" href="structISRVars.html#a9db372787f75f20b71f24706af08878e"> 140</a></span>  <span class="keyword">volatile</span> <span class="keywordtype">bool</span> <a class="code" href="structISRVars.html#a9db372787f75f20b71f24706af08878e">currDirection</a>;</div>
|
||||
<div class="line"><a name="l00141"></a><span class="lineno"><a class="line" href="structISRVars.html#a24a642bb0d154409a0c7799c6e79552a"> 141</a></span>  <span class="keywordtype">unsigned</span> <span class="keywordtype">char</span> <a class="code" href="structISRVars.html#a24a642bb0d154409a0c7799c6e79552a">pinIRQB</a>;</div>
|
||||
<div class="line"><a name="l00142"></a><span class="lineno"><a class="line" href="structISRVars.html#ac1eba4ab5f07f4751a050d9cbcedc797"> 142</a></span>  <span class="keywordtype">unsigned</span> <span class="keywordtype">char</span> <a class="code" href="structISRVars.html#ac1eba4ab5f07f4751a050d9cbcedc797">pinIRQ</a>; <span class="comment">// pinIRQA 201207</span></div>
|
||||
<div class="line"><a name="l00143"></a><span class="lineno"> 143</span> };</div>
|
||||
<div class="line"><a name="l00144"></a><span class="lineno"> 144</span>  </div>
|
||||
<div class="line"><a name="l00145"></a><span class="lineno"><a class="line" href="classMotor.html"> 145</a></span> <span class="keyword">class </span><a class="code" href="classMotor.html">Motor</a>: <span class="keyword">public</span> <a class="code" href="classPID.html">PID</a> {</div>
|
||||
<div class="line"><a name="l00146"></a><span class="lineno"> 146</span> <span class="keyword">public</span>:</div>
|
||||
<div class="line"><a name="l00147"></a><span class="lineno"> 147</span>  <a class="code" href="classMotor.html">Motor</a>(<span class="keywordtype">unsigned</span> <span class="keywordtype">char</span> _pinPWM,<span class="keywordtype">unsigned</span> <span class="keywordtype">char</span> _pinDir,</div>
|
||||
<div class="line"><a name="l00148"></a><span class="lineno"> 148</span>  <span class="keywordtype">unsigned</span> <span class="keywordtype">char</span> _pinIRQ,<span class="keywordtype">unsigned</span> <span class="keywordtype">char</span> _pinIRQB,</div>
|
||||
<div class="line"><a name="l00149"></a><span class="lineno"> 149</span>  <span class="keyword">struct</span> <a class="code" href="structISRVars.html">ISRVars</a>* _isr);</div>
|
||||
<div class="line"><a name="l00150"></a><span class="lineno"> 150</span>  </div>
|
||||
<div class="line"><a name="l00151"></a><span class="lineno"> 151</span>  <span class="keywordtype">void</span> <a class="code" href="classMotor.html#a826a3f1ffd48fd6f49d74caf7ad68dad">setupInterrupt</a>();</div>
|
||||
<div class="line"><a name="l00152"></a><span class="lineno"> 152</span>  </div>
|
||||
<div class="line"><a name="l00153"></a><span class="lineno"> 153</span>  <span class="keywordtype">unsigned</span> <span class="keywordtype">char</span> <a class="code" href="classMotor.html#ad02c1db58f8f247f4e8becc19d1c7054">getPinPWM</a>() <span class="keyword">const</span>;</div>
|
||||
<div class="line"><a name="l00154"></a><span class="lineno"> 154</span>  <span class="keywordtype">unsigned</span> <span class="keywordtype">char</span> <a class="code" href="classMotor.html#af085804880a48840dc3d1d088911695e">getPinDir</a>() <span class="keyword">const</span>;</div>
|
||||
<div class="line"><a name="l00155"></a><span class="lineno"> 155</span>  <span class="keywordtype">unsigned</span> <span class="keywordtype">char</span> <a class="code" href="classMotor.html#a785eadb656e31e62b1f1515004344ae0">getPinIRQ</a>() <span class="keyword">const</span>;</div>
|
||||
<div class="line"><a name="l00156"></a><span class="lineno"> 156</span>  <span class="keywordtype">unsigned</span> <span class="keywordtype">char</span> <a class="code" href="classMotor.html#a3a1771db56274e5c06625d33a098932f">getPinIRQB</a>() <span class="keyword">const</span>;</div>
|
||||
<div class="line"><a name="l00157"></a><span class="lineno"> 157</span>  </div>
|
||||
<div class="line"><a name="l00158"></a><span class="lineno"> 158</span>  <span class="keywordtype">unsigned</span> <span class="keywordtype">int</span> <a class="code" href="classMotor.html#ad4e09298c4c8b99ab467a4262d8a3207">runPWM</a>(<span class="keywordtype">unsigned</span> <span class="keywordtype">int</span> PWM,<span class="keywordtype">bool</span> dir,<span class="keywordtype">bool</span> saveDir=<span class="keyword">true</span>);</div>
|
||||
<div class="line"><a name="l00159"></a><span class="lineno"> 159</span>  <span class="keywordtype">unsigned</span> <span class="keywordtype">int</span> <a class="code" href="classMotor.html#aa41934a55ada6dabb95b6741b6d964d3">getPWM</a>() <span class="keyword">const</span>;</div>
|
||||
<div class="line"><a name="l00160"></a><span class="lineno"> 160</span>  <span class="keywordtype">unsigned</span> <span class="keywordtype">int</span> <a class="code" href="classMotor.html#a17f9e1e193961edc117026f80e806d49">advancePWM</a>(<span class="keywordtype">unsigned</span> <span class="keywordtype">int</span> PWM);</div>
|
||||
<div class="line"><a name="l00161"></a><span class="lineno"> 161</span>  <span class="keywordtype">unsigned</span> <span class="keywordtype">int</span> <a class="code" href="classMotor.html#aefe7b72985f51315c7ffe81fbf66869c">backoffPWM</a>(<span class="keywordtype">unsigned</span> <span class="keywordtype">int</span> PWM);</div>
|
||||
<div class="line"><a name="l00162"></a><span class="lineno"> 162</span>  </div>
|
||||
<div class="line"><a name="l00163"></a><span class="lineno"> 163</span>  <span class="keywordtype">bool</span> <a class="code" href="classMotor.html#a2aaead147c8cb1a712db027f9cb70e33">setDesiredDir</a>(<span class="keywordtype">bool</span> dir);</div>
|
||||
<div class="line"><a name="l00164"></a><span class="lineno"> 164</span>  <span class="keywordtype">bool</span> <a class="code" href="classMotor.html#aa813d431c39937e90e91f3ad2fbf625d">getDesiredDir</a>() <span class="keyword">const</span>;</div>
|
||||
<div class="line"><a name="l00165"></a><span class="lineno"> 165</span>  <span class="keywordtype">bool</span> <a class="code" href="classMotor.html#aeddf9353baeaa0ad9e6de0df5d3e73e8">reverseDesiredDir</a>();</div>
|
||||
<div class="line"><a name="l00166"></a><span class="lineno"> 166</span>  </div>
|
||||
<div class="line"><a name="l00167"></a><span class="lineno"> 167</span>  <span class="keywordtype">bool</span> <a class="code" href="classMotor.html#a9462d1a9af69941100f422ce1a0faeff">setCurrDir</a>();</div>
|
||||
<div class="line"><a name="l00168"></a><span class="lineno"> 168</span>  <span class="keywordtype">bool</span> <a class="code" href="classMotor.html#aaedede5ddae28b6926204dc7a47e0612">getCurrDir</a>() <span class="keyword">const</span>;</div>
|
||||
<div class="line"><a name="l00169"></a><span class="lineno"> 169</span>  </div>
|
||||
<div class="line"><a name="l00170"></a><span class="lineno"> 170</span>  <span class="comment">//int getAccRPMM() const; // Acceleration, Round Per Min^2</span></div>
|
||||
<div class="line"><a name="l00171"></a><span class="lineno"> 171</span>  <span class="comment">//unsigned int getSpeedRPM() const;</span></div>
|
||||
<div class="line"><a name="l00172"></a><span class="lineno"> 172</span>  <span class="comment">//unsigned int setSpeedRPM(int speedRPM,bool dir);</span></div>
|
||||
<div class="line"><a name="l00173"></a><span class="lineno"> 173</span>  <span class="comment">// direction sensitive 201208</span></div>
|
||||
<div class="line"><a name="l00174"></a><span class="lineno"> 174</span>  <span class="keywordtype">int</span> <a class="code" href="classMotor.html#ada15a2f02a7945a458b48e829b6a5d6b">getSpeedRPM</a>() <span class="keyword">const</span>;</div>
|
||||
<div class="line"><a name="l00175"></a><span class="lineno"> 175</span>  <span class="keywordtype">unsigned</span> <span class="keywordtype">int</span> <a class="code" href="classMotor.html#a8d707212e2395830a9064712df1c4f68">setSpeedRPM</a>(<span class="keywordtype">int</span> speedRPM,<span class="keywordtype">bool</span> dir); <span class="comment">// preserve</span></div>
|
||||
<div class="line"><a name="l00176"></a><span class="lineno"> 176</span>  <span class="keywordtype">int</span> <a class="code" href="classMotor.html#a8d707212e2395830a9064712df1c4f68">setSpeedRPM</a>(<span class="keywordtype">int</span> speedRPM);</div>
|
||||
<div class="line"><a name="l00177"></a><span class="lineno"> 177</span>  </div>
|
||||
<div class="line"><a name="l00178"></a><span class="lineno"> 178</span>  <span class="comment">//void simpleRegulate();</span></div>
|
||||
<div class="line"><a name="l00179"></a><span class="lineno"> 179</span>  </div>
|
||||
<div class="line"><a name="l00180"></a><span class="lineno"> 180</span>  <span class="keywordtype">bool</span> <a class="code" href="classMotor.html#a0555b6c2a33c373d3a9e33f174a2b5aa">PIDSetup</a>(<span class="keywordtype">float</span> kc=<a class="code" href="MotorWheel_8h.html#a73764abcca0b8bbf6bf355d9f1bab0b9">KC</a>,<span class="keywordtype">float</span> taui=<a class="code" href="MotorWheel_8h.html#a73c066690ee81cb3f9c801205a237acd">TAUI</a>,<span class="keywordtype">float</span> taud=<a class="code" href="MotorWheel_8h.html#a75450bf317fb4edd6c44dbe6b2ff7673">TAUD</a>,<span class="keywordtype">unsigned</span> <span class="keywordtype">int</span> sampleTime=1000);</div>
|
||||
<div class="line"><a name="l00181"></a><span class="lineno"> 181</span>  <span class="keywordtype">bool</span> <a class="code" href="classMotor.html#a1bc02b7e0da3aca6e724d2755d42eaab">PIDGetStatus</a>() <span class="keyword">const</span>;</div>
|
||||
<div class="line"><a name="l00182"></a><span class="lineno"> 182</span>  <span class="keywordtype">bool</span> <a class="code" href="classMotor.html#ad6ee53cd8570f60ae5dd83b8604b00fe">PIDEnable</a>(<span class="keywordtype">float</span> kc=<a class="code" href="MotorWheel_8h.html#a73764abcca0b8bbf6bf355d9f1bab0b9">KC</a>,<span class="keywordtype">float</span> taui=<a class="code" href="MotorWheel_8h.html#a73c066690ee81cb3f9c801205a237acd">TAUI</a>,<span class="keywordtype">float</span> taud=<a class="code" href="MotorWheel_8h.html#a75450bf317fb4edd6c44dbe6b2ff7673">TAUD</a>,<span class="keywordtype">unsigned</span> <span class="keywordtype">int</span> sampleTime=1000);</div>
|
||||
<div class="line"><a name="l00183"></a><span class="lineno"> 183</span>  <span class="keywordtype">bool</span> <a class="code" href="classMotor.html#a6358811a51b7636b06199972b7fae417">PIDDisable</a>();</div>
|
||||
<div class="line"><a name="l00184"></a><span class="lineno"> 184</span>  <span class="keywordtype">bool</span> <a class="code" href="classMotor.html#ae14f43483f26152d92c88aa4c6a7a471">PIDReset</a>();</div>
|
||||
<div class="line"><a name="l00185"></a><span class="lineno"> 185</span>  <span class="keywordtype">bool</span> <a class="code" href="classMotor.html#aa44fc307611e45eeb5e6fb50c79f375b">PIDRegulate</a>(<span class="keywordtype">bool</span> doRegulate=<span class="keyword">true</span>);</div>
|
||||
<div class="line"><a name="l00186"></a><span class="lineno"> 186</span>  <span class="keywordtype">unsigned</span> <span class="keywordtype">int</span> <a class="code" href="classMotor.html#a3377631cff641d41a50b7f1c5b30fc1f">PIDSetSpeedRPMDesired</a>(<span class="keywordtype">unsigned</span> <span class="keywordtype">int</span> speedRPM);</div>
|
||||
<div class="line"><a name="l00187"></a><span class="lineno"> 187</span>  <span class="keywordtype">unsigned</span> <span class="keywordtype">int</span> <a class="code" href="classMotor.html#a9ca625db156da95bc5f4500c294f8e83">PIDGetSpeedRPMDesired</a>() <span class="keyword">const</span>;</div>
|
||||
<div class="line"><a name="l00188"></a><span class="lineno"> 188</span>  </div>
|
||||
<div class="line"><a name="l00189"></a><span class="lineno"> 189</span>  <span class="keywordtype">void</span> <a class="code" href="classMotor.html#a0a420be82fa25f5b62b96f6805835d71">delayMS</a>(<span class="keywordtype">unsigned</span> <span class="keywordtype">int</span> ms,<span class="keywordtype">bool</span> <a class="code" href="MotorWheel_8h.html#aa8f0efe0d1ee33354f41f8898d0ee8dd">debug</a>=<span class="keyword">false</span>);</div>
|
||||
<div class="line"><a name="l00190"></a><span class="lineno"> 190</span>  <span class="keywordtype">void</span> <a class="code" href="classMotor.html#a55a0ba922517197fd01caac36c84c682">debugger</a>() <span class="keyword">const</span>;</div>
|
||||
<div class="line"><a name="l00191"></a><span class="lineno"> 191</span>  </div>
|
||||
<div class="line"><a name="l00192"></a><span class="lineno"> 192</span>  <span class="comment">//int getAccPPSS() const;</span></div>
|
||||
<div class="line"><a name="l00193"></a><span class="lineno"> 193</span>  <span class="keywordtype">int</span> <a class="code" href="classMotor.html#a5e5d272254ecd37a082fc467e9cd2610">getSpeedPPS</a>() <span class="keyword">const</span>;</div>
|
||||
<div class="line"><a name="l00194"></a><span class="lineno"> 194</span>  <span class="keywordtype">long</span> <a class="code" href="classMotor.html#a54f6cdff2ab028fdd2724fbf40c3f641">getCurrPulse</a>() <span class="keyword">const</span>;</div>
|
||||
<div class="line"><a name="l00195"></a><span class="lineno"> 195</span>  <span class="keywordtype">long</span> <a class="code" href="classMotor.html#a653642c0cba985a85204fbfe81cf3c8a">setCurrPulse</a>(<span class="keywordtype">long</span> _pulse);</div>
|
||||
<div class="line"><a name="l00196"></a><span class="lineno"> 196</span>  <span class="keywordtype">long</span> <a class="code" href="classMotor.html#a190bda1f77605d10bcbacceb2e465bf0">resetCurrPulse</a>();</div>
|
||||
<div class="line"><a name="l00197"></a><span class="lineno"> 197</span>  </div>
|
||||
<div class="line"><a name="l00198"></a><span class="lineno"><a class="line" href="classMotor.html#acab1e83ffdd286821aa69af770294fae"> 198</a></span>  <span class="keyword">struct </span><a class="code" href="structISRVars.html">ISRVars</a>* <a class="code" href="classMotor.html#acab1e83ffdd286821aa69af770294fae">isr</a>;</div>
|
||||
<div class="line"><a name="l00199"></a><span class="lineno"> 199</span>  </div>
|
||||
<div class="line"><a name="l00200"></a><span class="lineno"> 200</span> <span class="keyword">private</span>:</div>
|
||||
<div class="line"><a name="l00201"></a><span class="lineno"> 201</span>  <span class="keywordtype">unsigned</span> <span class="keywordtype">char</span> pinPWM;</div>
|
||||
<div class="line"><a name="l00202"></a><span class="lineno"> 202</span>  <span class="keywordtype">unsigned</span> <span class="keywordtype">char</span> pinDir;</div>
|
||||
<div class="line"><a name="l00203"></a><span class="lineno"> 203</span>  <span class="comment">//unsigned char pinIRQ; // moved to isr</span></div>
|
||||
<div class="line"><a name="l00204"></a><span class="lineno"> 204</span>  <span class="comment">//unsigned char pinIRQB;</span></div>
|
||||
<div class="line"><a name="l00205"></a><span class="lineno"> 205</span>  </div>
|
||||
<div class="line"><a name="l00206"></a><span class="lineno"> 206</span>  <span class="comment">//bool currDirection; // current direction</span></div>
|
||||
<div class="line"><a name="l00207"></a><span class="lineno"> 207</span>  <span class="keywordtype">bool</span> desiredDirection; <span class="comment">// desired direction</span></div>
|
||||
<div class="line"><a name="l00208"></a><span class="lineno"> 208</span>  <span class="keywordtype">unsigned</span> <span class="keywordtype">int</span> speedPWM; <span class="comment">// current PWM</span></div>
|
||||
<div class="line"><a name="l00209"></a><span class="lineno"> 209</span>  </div>
|
||||
<div class="line"><a name="l00210"></a><span class="lineno"> 210</span>  <span class="keywordtype">int</span> speedRPMInput; <span class="comment">// RPM: Round Per Minute</span></div>
|
||||
<div class="line"><a name="l00211"></a><span class="lineno"> 211</span>  <span class="keywordtype">int</span> speedRPMOutput; <span class="comment">// RPM</span></div>
|
||||
<div class="line"><a name="l00212"></a><span class="lineno"> 212</span>  <span class="keywordtype">int</span> speedRPMDesired; <span class="comment">// RPM</span></div>
|
||||
<div class="line"><a name="l00213"></a><span class="lineno"> 213</span>  <span class="comment">//float PWMEC;</span></div>
|
||||
<div class="line"><a name="l00214"></a><span class="lineno"> 214</span>  <span class="keywordtype">float</span> speed2DutyCycle;</div>
|
||||
<div class="line"><a name="l00215"></a><span class="lineno"> 215</span> <span class="comment">/*</span></div>
|
||||
<div class="line"><a name="l00216"></a><span class="lineno"> 216</span> <span class="comment"> // the followings are defined in struct ISRvars, </span></div>
|
||||
<div class="line"><a name="l00217"></a><span class="lineno"> 217</span> <span class="comment"> // because ISR must be a global function, without parameters and no return value</span></div>
|
||||
<div class="line"><a name="l00218"></a><span class="lineno"> 218</span> <span class="comment"></span> </div>
|
||||
<div class="line"><a name="l00219"></a><span class="lineno"> 219</span> <span class="comment"> volatile unsigned int speedPPS; // PPS: Pulses Per Second</span></div>
|
||||
<div class="line"><a name="l00220"></a><span class="lineno"> 220</span> <span class="comment"> volatile unsigned long pulseStartMicros;</span></div>
|
||||
<div class="line"><a name="l00221"></a><span class="lineno"> 221</span> <span class="comment"> volatile unsigned long pulseEndMicros;</span></div>
|
||||
<div class="line"><a name="l00222"></a><span class="lineno"> 222</span> <span class="comment"> */</span></div>
|
||||
<div class="line"><a name="l00223"></a><span class="lineno"> 223</span>  <span class="keywordtype">bool</span> pidCtrl;</div>
|
||||
<div class="line"><a name="l00224"></a><span class="lineno"> 224</span>  </div>
|
||||
<div class="line"><a name="l00225"></a><span class="lineno"> 225</span>  <a class="code" href="classMotor.html">Motor</a>();</div>
|
||||
<div class="line"><a name="l00226"></a><span class="lineno"> 226</span>  </div>
|
||||
<div class="line"><a name="l00227"></a><span class="lineno"> 227</span> };</div>
|
||||
<div class="line"><a name="l00228"></a><span class="lineno"> 228</span>  </div>
|
||||
<div class="line"><a name="l00229"></a><span class="lineno"> 229</span>  </div>
|
||||
<div class="line"><a name="l00230"></a><span class="lineno"> 230</span> <span class="preprocessor">#ifndef REDUCTION_RATIO</span></div>
|
||||
<div class="line"><a name="l00231"></a><span class="lineno"> 231</span> <span class="preprocessor">#define REDUCTION_RATIO 64</span></div>
|
||||
<div class="line"><a name="l00232"></a><span class="lineno"> 232</span> <span class="preprocessor">#endif</span></div>
|
||||
<div class="line"><a name="l00233"></a><span class="lineno"><a class="line" href="classGearedMotor.html"> 233</a></span> <span class="keyword">class </span><a class="code" href="classGearedMotor.html">GearedMotor</a>: <span class="keyword">public</span> <a class="code" href="classMotor.html">Motor</a> { <span class="comment">// RPM</span></div>
|
||||
<div class="line"><a name="l00234"></a><span class="lineno"> 234</span> <span class="keyword">public</span>:</div>
|
||||
<div class="line"><a name="l00235"></a><span class="lineno"> 235</span>  <a class="code" href="classGearedMotor.html#aa91e4c0799d41b33495cac9c805333e2">GearedMotor</a>(<span class="keywordtype">unsigned</span> <span class="keywordtype">char</span> _pinPWM,<span class="keywordtype">unsigned</span> <span class="keywordtype">char</span> _pinDir,</div>
|
||||
<div class="line"><a name="l00236"></a><span class="lineno"> 236</span>  <span class="keywordtype">unsigned</span> <span class="keywordtype">char</span> _pinIRQ,<span class="keywordtype">unsigned</span> <span class="keywordtype">char</span> _pinIRQB,</div>
|
||||
<div class="line"><a name="l00237"></a><span class="lineno"> 237</span>  <span class="keyword">struct</span> <a class="code" href="structISRVars.html">ISRVars</a>* _isr,</div>
|
||||
<div class="line"><a name="l00238"></a><span class="lineno"> 238</span>  <span class="keywordtype">unsigned</span> <span class="keywordtype">int</span> _ratio=<a class="code" href="MotorWheel_8h.html#a545c3d33941dafc6ffd8cd9a61f6fca4">REDUCTION_RATIO</a>);</div>
|
||||
<div class="line"><a name="l00239"></a><span class="lineno"> 239</span>  <span class="comment">//float getGearedAccRPMM() const; // Acceleration, Round Per Min^2</span></div>
|
||||
<div class="line"><a name="l00240"></a><span class="lineno"> 240</span>  <span class="keywordtype">float</span> <a class="code" href="classGearedMotor.html#a13b6c99ef8713b5333f98a9ba844ba8b">getGearedSpeedRPM</a>() <span class="keyword">const</span>;</div>
|
||||
<div class="line"><a name="l00241"></a><span class="lineno"> 241</span>  <span class="keywordtype">float</span> <a class="code" href="classGearedMotor.html#a0aa18eb91d0313f4bf64cc5e3d43c4cf">setGearedSpeedRPM</a>(<span class="keywordtype">float</span> gearedSpeedRPM,<span class="keywordtype">bool</span> dir);</div>
|
||||
<div class="line"><a name="l00242"></a><span class="lineno"> 242</span>  <span class="comment">// direction sensitive 201208</span></div>
|
||||
<div class="line"><a name="l00243"></a><span class="lineno"> 243</span>  <span class="keywordtype">float</span> <a class="code" href="classGearedMotor.html#a0aa18eb91d0313f4bf64cc5e3d43c4cf">setGearedSpeedRPM</a>(<span class="keywordtype">float</span> gearedSpeedRPM);</div>
|
||||
<div class="line"><a name="l00244"></a><span class="lineno"> 244</span>  <span class="keywordtype">unsigned</span> <span class="keywordtype">int</span> <a class="code" href="classGearedMotor.html#aff9f697effb8c62667a32942ae154053">getRatio</a>() <span class="keyword">const</span>;</div>
|
||||
<div class="line"><a name="l00245"></a><span class="lineno"> 245</span>  <span class="keywordtype">unsigned</span> <span class="keywordtype">int</span> <a class="code" href="classGearedMotor.html#a347d79fb74710a1a82410d0b14a84f25">setRatio</a>(<span class="keywordtype">unsigned</span> <span class="keywordtype">int</span> ratio=<a class="code" href="MotorWheel_8h.html#a545c3d33941dafc6ffd8cd9a61f6fca4">REDUCTION_RATIO</a>);</div>
|
||||
<div class="line"><a name="l00246"></a><span class="lineno"> 246</span>  <span class="keywordtype">float</span> <a class="code" href="classGearedMotor.html#a36d9fc91b484c923d3f6c92d05c17b56">getPosition</a>();</div>
|
||||
<div class="line"><a name="l00247"></a><span class="lineno"> 247</span> <span class="keyword">private</span>:</div>
|
||||
<div class="line"><a name="l00248"></a><span class="lineno"> 248</span>  <span class="keywordtype">unsigned</span> <span class="keywordtype">int</span> _ratio;</div>
|
||||
<div class="line"><a name="l00249"></a><span class="lineno"> 249</span> };</div>
|
||||
<div class="line"><a name="l00250"></a><span class="lineno"> 250</span>  </div>
|
||||
<div class="line"><a name="l00251"></a><span class="lineno"> 251</span>  </div>
|
||||
<div class="line"><a name="l00252"></a><span class="lineno"> 252</span> <span class="preprocessor">#ifndef PI</span></div>
|
||||
<div class="line"><a name="l00253"></a><span class="lineno"><a class="line" href="MotorWheel_8h.html#a598a3330b3c21701223ee0ca14316eca"> 253</a></span> <span class="preprocessor">#define PI 3.1416</span></div>
|
||||
<div class="line"><a name="l00254"></a><span class="lineno"> 254</span> <span class="preprocessor">#endif</span></div>
|
||||
<div class="line"><a name="l00255"></a><span class="lineno"> 255</span> <span class="comment">//#define CIR 31.4 // cm</span></div>
|
||||
<div class="line"><a name="l00256"></a><span class="lineno"> 256</span> <span class="comment">//#define CIRMM 150 // mm</span></div>
|
||||
<div class="line"><a name="l00257"></a><span class="lineno"> 257</span> <span class="comment">//#define CIRMM 188</span></div>
|
||||
<div class="line"><a name="l00258"></a><span class="lineno"><a class="line" href="MotorWheel_8h.html#a557b8031c21a790194ec252c281dc404"> 258</a></span> <span class="preprocessor">#define CIRMM 314</span></div>
|
||||
<div class="line"><a name="l00259"></a><span class="lineno"><a class="line" href="classMotorWheel.html"> 259</a></span> <span class="keyword">class </span><a class="code" href="classMotorWheel.html">MotorWheel</a>: <span class="keyword">public</span> <a class="code" href="classGearedMotor.html">GearedMotor</a> { <span class="comment">// </span></div>
|
||||
<div class="line"><a name="l00260"></a><span class="lineno"> 260</span> <span class="keyword">public</span>:</div>
|
||||
<div class="line"><a name="l00261"></a><span class="lineno"> 261</span>  <a class="code" href="classMotorWheel.html#a51b83bdbd1880690814b3febb790484b">MotorWheel</a>(<span class="keywordtype">unsigned</span> <span class="keywordtype">char</span> _pinPWM,<span class="keywordtype">unsigned</span> <span class="keywordtype">char</span> _pinDir,</div>
|
||||
<div class="line"><a name="l00262"></a><span class="lineno"> 262</span>  <span class="keywordtype">unsigned</span> <span class="keywordtype">char</span> _pinIRQ,<span class="keywordtype">unsigned</span> <span class="keywordtype">char</span> _pinIRQB,</div>
|
||||
<div class="line"><a name="l00263"></a><span class="lineno"> 263</span>  <span class="keyword">struct</span> <a class="code" href="structISRVars.html">ISRVars</a>* _isr,</div>
|
||||
<div class="line"><a name="l00264"></a><span class="lineno"> 264</span>  <span class="keywordtype">unsigned</span> <span class="keywordtype">int</span> ratio=<a class="code" href="MotorWheel_8h.html#a545c3d33941dafc6ffd8cd9a61f6fca4">REDUCTION_RATIO</a>,<span class="keywordtype">unsigned</span> <span class="keywordtype">int</span> cirMM=<a class="code" href="MotorWheel_8h.html#a557b8031c21a790194ec252c281dc404">CIRMM</a>);</div>
|
||||
<div class="line"><a name="l00265"></a><span class="lineno"> 265</span>  </div>
|
||||
<div class="line"><a name="l00266"></a><span class="lineno"> 266</span>  <span class="keywordtype">unsigned</span> <span class="keywordtype">int</span> <a class="code" href="classMotorWheel.html#ae3ceed8768efd5e263e1b897b14b6a6b">getCirMM</a>() <span class="keyword">const</span>;</div>
|
||||
<div class="line"><a name="l00267"></a><span class="lineno"> 267</span>  <span class="keywordtype">unsigned</span> <span class="keywordtype">int</span> <a class="code" href="classMotorWheel.html#a6f2191d032f70f43cf60818d1e9c6b66">setCirMM</a>(<span class="keywordtype">unsigned</span> <span class="keywordtype">int</span> cirMM=<a class="code" href="MotorWheel_8h.html#a557b8031c21a790194ec252c281dc404">CIRMM</a>);</div>
|
||||
<div class="line"><a name="l00268"></a><span class="lineno"> 268</span> <span class="comment">/*</span></div>
|
||||
<div class="line"><a name="l00269"></a><span class="lineno"> 269</span> <span class="comment"> int getAccCMPMM() const; // Acceleration, CM Per Min^2</span></div>
|
||||
<div class="line"><a name="l00270"></a><span class="lineno"> 270</span> <span class="comment"> unsigned int getSpeedCMPM() const; // cm/min</span></div>
|
||||
<div class="line"><a name="l00271"></a><span class="lineno"> 271</span> <span class="comment"> unsigned int setSpeedCMPM(unsigned int cm,bool dir);</span></div>
|
||||
<div class="line"><a name="l00272"></a><span class="lineno"> 272</span> <span class="comment"> int getAccMMPSS() const; // Acceleration, MM Per Sec^2</span></div>
|
||||
<div class="line"><a name="l00273"></a><span class="lineno"> 273</span> <span class="comment"> unsigned int getSpeedMMPS() const; // mm/s</span></div>
|
||||
<div class="line"><a name="l00274"></a><span class="lineno"> 274</span> <span class="comment"> unsigned int setSpeedMMPS(unsigned int mm,bool dir);</span></div>
|
||||
<div class="line"><a name="l00275"></a><span class="lineno"> 275</span> <span class="comment"> */</span></div>
|
||||
<div class="line"><a name="l00276"></a><span class="lineno"> 276</span>  <span class="comment">// direction sensitive 201208</span></div>
|
||||
<div class="line"><a name="l00277"></a><span class="lineno"> 277</span>  <span class="comment">//int getAccCMPMM() const; // Acceleration, CM Per Min^2</span></div>
|
||||
<div class="line"><a name="l00278"></a><span class="lineno"> 278</span>  <span class="keywordtype">int</span> <a class="code" href="classMotorWheel.html#a8c38bc7d114f802169562d32d1f1bbaa">getSpeedCMPM</a>() <span class="keyword">const</span>; <span class="comment">// cm/min</span></div>
|
||||
<div class="line"><a name="l00279"></a><span class="lineno"> 279</span>  <span class="keywordtype">int</span> <a class="code" href="classMotorWheel.html#a9f2e423db798c68453624aba49c368e1">setSpeedCMPM</a>(<span class="keywordtype">unsigned</span> <span class="keywordtype">int</span> cm,<span class="keywordtype">bool</span> dir); <span class="comment">// preserve</span></div>
|
||||
<div class="line"><a name="l00280"></a><span class="lineno"> 280</span>  <span class="keywordtype">int</span> <a class="code" href="classMotorWheel.html#a9f2e423db798c68453624aba49c368e1">setSpeedCMPM</a>(<span class="keywordtype">int</span> cm);</div>
|
||||
<div class="line"><a name="l00281"></a><span class="lineno"> 281</span>  <span class="comment">//int getAccMMPSS() const; // Acceleration, MM Per Sec^2</span></div>
|
||||
<div class="line"><a name="l00282"></a><span class="lineno"> 282</span>  <span class="keywordtype">int</span> <a class="code" href="classMotorWheel.html#a6cec55acabda4ae12a8d66d4b50a7e39">getSpeedMMPS</a>() <span class="keyword">const</span>; <span class="comment">// mm/s</span></div>
|
||||
<div class="line"><a name="l00283"></a><span class="lineno"> 283</span>  <span class="keywordtype">int</span> <a class="code" href="classMotorWheel.html#a41d7f56c8abd6e75ae9df4f015e7873d">setSpeedMMPS</a>(<span class="keywordtype">unsigned</span> <span class="keywordtype">int</span> mm,<span class="keywordtype">bool</span> dir); <span class="comment">// preserve</span></div>
|
||||
<div class="line"><a name="l00284"></a><span class="lineno"> 284</span>  <span class="keywordtype">int</span> <a class="code" href="classMotorWheel.html#a41d7f56c8abd6e75ae9df4f015e7873d">setSpeedMMPS</a>(<span class="keywordtype">int</span> mm);</div>
|
||||
<div class="line"><a name="l00285"></a><span class="lineno"> 285</span>  <span class="keywordtype">void</span> <a class="code" href="classMotorWheel.html#a1ce67716650175c1be697fc7932b9937">setGearedRPM</a>(<span class="keywordtype">float</span> rpm, <span class="keywordtype">bool</span> dir);</div>
|
||||
<div class="line"><a name="l00286"></a><span class="lineno"> 286</span>  </div>
|
||||
<div class="line"><a name="l00287"></a><span class="lineno"> 287</span>  <span class="comment">//unsigned int runTime(unsigned int speedMMPS,bool dir,unsigned int TimeMS);</span></div>
|
||||
<div class="line"><a name="l00288"></a><span class="lineno"> 288</span>  <span class="comment">//unsigned int runDistance(unsigned int speedMMPS,bool dir,unsigned int distanceMM);</span></div>
|
||||
<div class="line"><a name="l00289"></a><span class="lineno"> 289</span>  </div>
|
||||
<div class="line"><a name="l00290"></a><span class="lineno"> 290</span> <span class="keyword">private</span>:</div>
|
||||
<div class="line"><a name="l00291"></a><span class="lineno"> 291</span>  <span class="keywordtype">unsigned</span> <span class="keywordtype">int</span> _cirMM;</div>
|
||||
<div class="line"><a name="l00292"></a><span class="lineno"> 292</span> };</div>
|
||||
<div class="line"><a name="l00293"></a><span class="lineno"> 293</span>  </div>
|
||||
<div class="line"><a name="l00294"></a><span class="lineno"> 294</span> <span class="comment">/*</span></div>
|
||||
<div class="line"><a name="l00295"></a><span class="lineno"> 295</span> <span class="comment">class samePID: public PID {</span></div>
|
||||
<div class="line"><a name="l00296"></a><span class="lineno"> 296</span> <span class="comment">public:</span></div>
|
||||
<div class="line"><a name="l00297"></a><span class="lineno"> 297</span> <span class="comment"> samePID(int* input,int* output,int* setPoint,float kc,float taui,float taud)</span></div>
|
||||
<div class="line"><a name="l00298"></a><span class="lineno"> 298</span> <span class="comment"> :PID(input,output,setPoint,kc,taui,taud) { }</span></div>
|
||||
<div class="line"><a name="l00299"></a><span class="lineno"> 299</span> <span class="comment">};</span></div>
|
||||
<div class="line"><a name="l00300"></a><span class="lineno"> 300</span> <span class="comment"></span> </div>
|
||||
<div class="line"><a name="l00301"></a><span class="lineno"> 301</span> <span class="comment">class servoMotor: public Motor,public samePID {</span></div>
|
||||
<div class="line"><a name="l00302"></a><span class="lineno"> 302</span> <span class="comment">public:</span></div>
|
||||
<div class="line"><a name="l00303"></a><span class="lineno"> 303</span> <span class="comment"> servoMotor(unsigned char _pinPWM,unsigned char _pinDir,</span></div>
|
||||
<div class="line"><a name="l00304"></a><span class="lineno"> 304</span> <span class="comment"> unsigned char _pinIRQ,unsigned char _pinIRQB,</span></div>
|
||||
<div class="line"><a name="l00305"></a><span class="lineno"> 305</span> <span class="comment"> struct ISRVars* _isr);</span></div>
|
||||
<div class="line"><a name="l00306"></a><span class="lineno"> 306</span> <span class="comment"></span> </div>
|
||||
<div class="line"><a name="l00307"></a><span class="lineno"> 307</span> <span class="comment"> int SPIDSetPulseBoundary(int min,int max);</span></div>
|
||||
<div class="line"><a name="l00308"></a><span class="lineno"> 308</span> <span class="comment"> bool SPIDSetup(float kc=KC,float taui=TAUI,float taud=TAUD,unsigned int sampleTime=10);</span></div>
|
||||
<div class="line"><a name="l00309"></a><span class="lineno"> 309</span> <span class="comment"> bool PIDRegulate(bool doRegulate=true);</span></div>
|
||||
<div class="line"><a name="l00310"></a><span class="lineno"> 310</span> <span class="comment"></span> </div>
|
||||
<div class="line"><a name="l00311"></a><span class="lineno"> 311</span> <span class="comment"> enum {</span></div>
|
||||
<div class="line"><a name="l00312"></a><span class="lineno"> 312</span> <span class="comment"> SPIDMODE_UNKNOWN,</span></div>
|
||||
<div class="line"><a name="l00313"></a><span class="lineno"> 313</span> <span class="comment"> SPIDMODE_SPEED,</span></div>
|
||||
<div class="line"><a name="l00314"></a><span class="lineno"> 314</span> <span class="comment"> SPIDMODE_STOP,</span></div>
|
||||
<div class="line"><a name="l00315"></a><span class="lineno"> 315</span> <span class="comment"> SPIDMODE_PULSE,</span></div>
|
||||
<div class="line"><a name="l00316"></a><span class="lineno"> 316</span> <span class="comment"> };</span></div>
|
||||
<div class="line"><a name="l00317"></a><span class="lineno"> 317</span> <span class="comment"> unsigned char getSPIDMode() const;</span></div>
|
||||
<div class="line"><a name="l00318"></a><span class="lineno"> 318</span> <span class="comment"> unsigned char setSPIDMode(unsigned char _mode);</span></div>
|
||||
<div class="line"><a name="l00319"></a><span class="lineno"> 319</span> <span class="comment"></span> </div>
|
||||
<div class="line"><a name="l00320"></a><span class="lineno"> 320</span> <span class="comment"> int getPulseDesired() const;</span></div>
|
||||
<div class="line"><a name="l00321"></a><span class="lineno"> 321</span> <span class="comment"> int setPulseDesired(int _pulse);</span></div>
|
||||
<div class="line"><a name="l00322"></a><span class="lineno"> 322</span> <span class="comment"> int incPulseDesired();</span></div>
|
||||
<div class="line"><a name="l00323"></a><span class="lineno"> 323</span> <span class="comment"> int decPulseDesired();</span></div>
|
||||
<div class="line"><a name="l00324"></a><span class="lineno"> 324</span> <span class="comment"></span> </div>
|
||||
<div class="line"><a name="l00325"></a><span class="lineno"> 325</span> <span class="comment"> bool backToZero();</span></div>
|
||||
<div class="line"><a name="l00326"></a><span class="lineno"> 326</span> <span class="comment"> bool scanZero();</span></div>
|
||||
<div class="line"><a name="l00327"></a><span class="lineno"> 327</span> <span class="comment"></span> </div>
|
||||
<div class="line"><a name="l00328"></a><span class="lineno"> 328</span> <span class="comment"> void debugger() const;</span></div>
|
||||
<div class="line"><a name="l00329"></a><span class="lineno"> 329</span> <span class="comment"></span> </div>
|
||||
<div class="line"><a name="l00330"></a><span class="lineno"> 330</span> <span class="comment">private:</span></div>
|
||||
<div class="line"><a name="l00331"></a><span class="lineno"> 331</span> <span class="comment"> int pulseInput; //</span></div>
|
||||
<div class="line"><a name="l00332"></a><span class="lineno"> 332</span> <span class="comment"> int pulseOutput; //</span></div>
|
||||
<div class="line"><a name="l00333"></a><span class="lineno"> 333</span> <span class="comment"> int pulseDesired; //</span></div>
|
||||
<div class="line"><a name="l00334"></a><span class="lineno"> 334</span> <span class="comment"></span> </div>
|
||||
<div class="line"><a name="l00335"></a><span class="lineno"> 335</span> <span class="comment"> int pulse2SpeedRPM;</span></div>
|
||||
<div class="line"><a name="l00336"></a><span class="lineno"> 336</span> <span class="comment"></span> </div>
|
||||
<div class="line"><a name="l00337"></a><span class="lineno"> 337</span> <span class="comment"> unsigned char SPIDMode;</span></div>
|
||||
<div class="line"><a name="l00338"></a><span class="lineno"> 338</span> <span class="comment"></span> </div>
|
||||
<div class="line"><a name="l00339"></a><span class="lineno"> 339</span> <span class="comment"> bool SPIDRegulateSpeed(bool doRegulate=true); // 201104</span></div>
|
||||
<div class="line"><a name="l00340"></a><span class="lineno"> 340</span> <span class="comment"> bool SPIDRegulateStop(bool doRegulate=true);</span></div>
|
||||
<div class="line"><a name="l00341"></a><span class="lineno"> 341</span> <span class="comment"> bool SPIDRegulatePulse(bool doRegulate=true);</span></div>
|
||||
<div class="line"><a name="l00342"></a><span class="lineno"> 342</span> <span class="comment"></span> </div>
|
||||
<div class="line"><a name="l00343"></a><span class="lineno"> 343</span> <span class="comment">};</span></div>
|
||||
<div class="line"><a name="l00344"></a><span class="lineno"> 344</span> <span class="comment"> */</span></div>
|
||||
<div class="line"><a name="l00345"></a><span class="lineno"> 345</span>  </div>
|
||||
<div class="line"><a name="l00346"></a><span class="lineno"> 346</span>  </div>
|
||||
<div class="line"><a name="l00347"></a><span class="lineno"> 347</span>  </div>
|
||||
<div class="line"><a name="l00348"></a><span class="lineno"> 348</span> <span class="preprocessor">#endif</span></div>
|
||||
<div class="line"><a name="l00349"></a><span class="lineno"> 349</span>  </div>
|
||||
<div class="ttc" id="aMotorWheel_8h_html_a545c3d33941dafc6ffd8cd9a61f6fca4"><div class="ttname"><a href="MotorWheel_8h.html#a545c3d33941dafc6ffd8cd9a61f6fca4">REDUCTION_RATIO</a></div><div class="ttdeci">#define REDUCTION_RATIO</div><div class="ttdef"><b>Definition:</b> MotorWheel.h:77</div></div>
|
||||
<div class="ttc" id="aMotorWheel_8h_html_a557b8031c21a790194ec252c281dc404"><div class="ttname"><a href="MotorWheel_8h.html#a557b8031c21a790194ec252c281dc404">CIRMM</a></div><div class="ttdeci">#define CIRMM</div><div class="ttdef"><b>Definition:</b> MotorWheel.h:258</div></div>
|
||||
<div class="ttc" id="aMotorWheel_8h_html_a73764abcca0b8bbf6bf355d9f1bab0b9"><div class="ttname"><a href="MotorWheel_8h.html#a73764abcca0b8bbf6bf355d9f1bab0b9">KC</a></div><div class="ttdeci">#define KC</div><div class="ttdef"><b>Definition:</b> MotorWheel.h:93</div></div>
|
||||
<div class="ttc" id="aMotorWheel_8h_html_a73c066690ee81cb3f9c801205a237acd"><div class="ttname"><a href="MotorWheel_8h.html#a73c066690ee81cb3f9c801205a237acd">TAUI</a></div><div class="ttdeci">#define TAUI</div><div class="ttdef"><b>Definition:</b> MotorWheel.h:94</div></div>
|
||||
<div class="ttc" id="aMotorWheel_8h_html_a75450bf317fb4edd6c44dbe6b2ff7673"><div class="ttname"><a href="MotorWheel_8h.html#a75450bf317fb4edd6c44dbe6b2ff7673">TAUD</a></div><div class="ttdeci">#define TAUD</div><div class="ttdef"><b>Definition:</b> MotorWheel.h:95</div></div>
|
||||
<div class="ttc" id="aMotorWheel_8h_html_aa8f0efe0d1ee33354f41f8898d0ee8dd"><div class="ttname"><a href="MotorWheel_8h.html#aa8f0efe0d1ee33354f41f8898d0ee8dd">debug</a></div><div class="ttdeci">#define debug()</div><div class="ttdef"><b>Definition:</b> MotorWheel.h:109</div></div>
|
||||
<div class="ttc" id="aPID__Beta6_8h_html"><div class="ttname"><a href="PID__Beta6_8h.html">PID_Beta6.h</a></div></div>
|
||||
<div class="ttc" id="aPinChangeInt_8h_html"><div class="ttname"><a href="PinChangeInt_8h.html">PinChangeInt.h</a></div></div>
|
||||
<div class="ttc" id="aclassGearedMotor_html"><div class="ttname"><a href="classGearedMotor.html">GearedMotor</a></div><div class="ttdef"><b>Definition:</b> MotorWheel.h:233</div></div>
|
||||
<div class="ttc" id="aclassGearedMotor_html_a0aa18eb91d0313f4bf64cc5e3d43c4cf"><div class="ttname"><a href="classGearedMotor.html#a0aa18eb91d0313f4bf64cc5e3d43c4cf">GearedMotor::setGearedSpeedRPM</a></div><div class="ttdeci">float setGearedSpeedRPM(float gearedSpeedRPM, bool dir)</div><div class="ttdef"><b>Definition:</b> MotorWheel.cpp:309</div></div>
|
||||
<div class="ttc" id="aclassGearedMotor_html_a13b6c99ef8713b5333f98a9ba844ba8b"><div class="ttname"><a href="classGearedMotor.html#a13b6c99ef8713b5333f98a9ba844ba8b">GearedMotor::getGearedSpeedRPM</a></div><div class="ttdeci">float getGearedSpeedRPM() const</div><div class="ttdef"><b>Definition:</b> MotorWheel.cpp:303</div></div>
|
||||
<div class="ttc" id="aclassGearedMotor_html_a347d79fb74710a1a82410d0b14a84f25"><div class="ttname"><a href="classGearedMotor.html#a347d79fb74710a1a82410d0b14a84f25">GearedMotor::setRatio</a></div><div class="ttdeci">unsigned int setRatio(unsigned int ratio=REDUCTION_RATIO)</div><div class="ttdef"><b>Definition:</b> MotorWheel.cpp:293</div></div>
|
||||
<div class="ttc" id="aclassGearedMotor_html_a36d9fc91b484c923d3f6c92d05c17b56"><div class="ttname"><a href="classGearedMotor.html#a36d9fc91b484c923d3f6c92d05c17b56">GearedMotor::getPosition</a></div><div class="ttdeci">float getPosition()</div><div class="ttdef"><b>Definition:</b> MotorWheel.cpp:323</div></div>
|
||||
<div class="ttc" id="aclassGearedMotor_html_aa91e4c0799d41b33495cac9c805333e2"><div class="ttname"><a href="classGearedMotor.html#aa91e4c0799d41b33495cac9c805333e2">GearedMotor::GearedMotor</a></div><div class="ttdeci">GearedMotor(unsigned char _pinPWM, unsigned char _pinDir, unsigned char _pinIRQ, unsigned char _pinIRQB, struct ISRVars *_isr, unsigned int _ratio=REDUCTION_RATIO)</div><div class="ttdef"><b>Definition:</b> MotorWheel.cpp:284</div></div>
|
||||
<div class="ttc" id="aclassGearedMotor_html_aff9f697effb8c62667a32942ae154053"><div class="ttname"><a href="classGearedMotor.html#aff9f697effb8c62667a32942ae154053">GearedMotor::getRatio</a></div><div class="ttdeci">unsigned int getRatio() const</div><div class="ttdef"><b>Definition:</b> MotorWheel.cpp:290</div></div>
|
||||
<div class="ttc" id="aclassMotorWheel_html"><div class="ttname"><a href="classMotorWheel.html">MotorWheel</a></div><div class="ttdef"><b>Definition:</b> MotorWheel.h:259</div></div>
|
||||
<div class="ttc" id="aclassMotorWheel_html_a1ce67716650175c1be697fc7932b9937"><div class="ttname"><a href="classMotorWheel.html#a1ce67716650175c1be697fc7932b9937">MotorWheel::setGearedRPM</a></div><div class="ttdeci">void setGearedRPM(float rpm, bool dir)</div><div class="ttdef"><b>Definition:</b> MotorWheel.cpp:364</div></div>
|
||||
<div class="ttc" id="aclassMotorWheel_html_a41d7f56c8abd6e75ae9df4f015e7873d"><div class="ttname"><a href="classMotorWheel.html#a41d7f56c8abd6e75ae9df4f015e7873d">MotorWheel::setSpeedMMPS</a></div><div class="ttdeci">int setSpeedMMPS(unsigned int mm, bool dir)</div><div class="ttdef"><b>Definition:</b> MotorWheel.cpp:375</div></div>
|
||||
<div class="ttc" id="aclassMotorWheel_html_a51b83bdbd1880690814b3febb790484b"><div class="ttname"><a href="classMotorWheel.html#a51b83bdbd1880690814b3febb790484b">MotorWheel::MotorWheel</a></div><div class="ttdeci">MotorWheel(unsigned char _pinPWM, unsigned char _pinDir, unsigned char _pinIRQ, unsigned char _pinIRQB, struct ISRVars *_isr, unsigned int ratio=REDUCTION_RATIO, unsigned int cirMM=CIRMM)</div><div class="ttdef"><b>Definition:</b> MotorWheel.cpp:329</div></div>
|
||||
<div class="ttc" id="aclassMotorWheel_html_a6cec55acabda4ae12a8d66d4b50a7e39"><div class="ttname"><a href="classMotorWheel.html#a6cec55acabda4ae12a8d66d4b50a7e39">MotorWheel::getSpeedMMPS</a></div><div class="ttdeci">int getSpeedMMPS() const</div><div class="ttdef"><b>Definition:</b> MotorWheel.cpp:370</div></div>
|
||||
<div class="ttc" id="aclassMotorWheel_html_a6f2191d032f70f43cf60818d1e9c6b66"><div class="ttname"><a href="classMotorWheel.html#a6f2191d032f70f43cf60818d1e9c6b66">MotorWheel::setCirMM</a></div><div class="ttdeci">unsigned int setCirMM(unsigned int cirMM=CIRMM)</div><div class="ttdef"><b>Definition:</b> MotorWheel.cpp:340</div></div>
|
||||
<div class="ttc" id="aclassMotorWheel_html_a8c38bc7d114f802169562d32d1f1bbaa"><div class="ttname"><a href="classMotorWheel.html#a8c38bc7d114f802169562d32d1f1bbaa">MotorWheel::getSpeedCMPM</a></div><div class="ttdeci">int getSpeedCMPM() const</div><div class="ttdef"><b>Definition:</b> MotorWheel.cpp:345</div></div>
|
||||
<div class="ttc" id="aclassMotorWheel_html_a9f2e423db798c68453624aba49c368e1"><div class="ttname"><a href="classMotorWheel.html#a9f2e423db798c68453624aba49c368e1">MotorWheel::setSpeedCMPM</a></div><div class="ttdeci">int setSpeedCMPM(unsigned int cm, bool dir)</div><div class="ttdef"><b>Definition:</b> MotorWheel.cpp:350</div></div>
|
||||
<div class="ttc" id="aclassMotorWheel_html_ae3ceed8768efd5e263e1b897b14b6a6b"><div class="ttname"><a href="classMotorWheel.html#ae3ceed8768efd5e263e1b897b14b6a6b">MotorWheel::getCirMM</a></div><div class="ttdeci">unsigned int getCirMM() const</div><div class="ttdef"><b>Definition:</b> MotorWheel.cpp:337</div></div>
|
||||
<div class="ttc" id="aclassMotor_html"><div class="ttname"><a href="classMotor.html">Motor</a></div><div class="ttdef"><b>Definition:</b> MotorWheel.h:145</div></div>
|
||||
<div class="ttc" id="aclassMotor_html_a0555b6c2a33c373d3a9e33f174a2b5aa"><div class="ttname"><a href="classMotor.html#a0555b6c2a33c373d3a9e33f174a2b5aa">Motor::PIDSetup</a></div><div class="ttdeci">bool PIDSetup(float kc=KC, float taui=TAUI, float taud=TAUD, unsigned int sampleTime=1000)</div><div class="ttdef"><b>Definition:</b> MotorWheel.cpp:171</div></div>
|
||||
<div class="ttc" id="aclassMotor_html_a0a420be82fa25f5b62b96f6805835d71"><div class="ttname"><a href="classMotor.html#a0a420be82fa25f5b62b96f6805835d71">Motor::delayMS</a></div><div class="ttdeci">void delayMS(unsigned int ms, bool debug=false)</div><div class="ttdef"><b>Definition:</b> MotorWheel.cpp:230</div></div>
|
||||
<div class="ttc" id="aclassMotor_html_a17f9e1e193961edc117026f80e806d49"><div class="ttname"><a href="classMotor.html#a17f9e1e193961edc117026f80e806d49">Motor::advancePWM</a></div><div class="ttdeci">unsigned int advancePWM(unsigned int PWM)</div><div class="ttdef"><b>Definition:</b> MotorWheel.cpp:80</div></div>
|
||||
<div class="ttc" id="aclassMotor_html_a190bda1f77605d10bcbacceb2e465bf0"><div class="ttname"><a href="classMotor.html#a190bda1f77605d10bcbacceb2e465bf0">Motor::resetCurrPulse</a></div><div class="ttdeci">long resetCurrPulse()</div><div class="ttdef"><b>Definition:</b> MotorWheel.cpp:226</div></div>
|
||||
<div class="ttc" id="aclassMotor_html_a1bc02b7e0da3aca6e724d2755d42eaab"><div class="ttname"><a href="classMotor.html#a1bc02b7e0da3aca6e724d2755d42eaab">Motor::PIDGetStatus</a></div><div class="ttdeci">bool PIDGetStatus() const</div><div class="ttdef"><b>Definition:</b> MotorWheel.cpp:149</div></div>
|
||||
<div class="ttc" id="aclassMotor_html_a2aaead147c8cb1a712db027f9cb70e33"><div class="ttname"><a href="classMotor.html#a2aaead147c8cb1a712db027f9cb70e33">Motor::setDesiredDir</a></div><div class="ttdeci">bool setDesiredDir(bool dir)</div><div class="ttdef"><b>Definition:</b> MotorWheel.cpp:92</div></div>
|
||||
<div class="ttc" id="aclassMotor_html_a3377631cff641d41a50b7f1c5b30fc1f"><div class="ttname"><a href="classMotor.html#a3377631cff641d41a50b7f1c5b30fc1f">Motor::PIDSetSpeedRPMDesired</a></div><div class="ttdeci">unsigned int PIDSetSpeedRPMDesired(unsigned int speedRPM)</div><div class="ttdef"><b>Definition:</b> MotorWheel.cpp:180</div></div>
|
||||
<div class="ttc" id="aclassMotor_html_a3a1771db56274e5c06625d33a098932f"><div class="ttname"><a href="classMotor.html#a3a1771db56274e5c06625d33a098932f">Motor::getPinIRQB</a></div><div class="ttdeci">unsigned char getPinIRQB() const</div><div class="ttdef"><b>Definition:</b> MotorWheel.cpp:67</div></div>
|
||||
<div class="ttc" id="aclassMotor_html_a54f6cdff2ab028fdd2724fbf40c3f641"><div class="ttname"><a href="classMotor.html#a54f6cdff2ab028fdd2724fbf40c3f641">Motor::getCurrPulse</a></div><div class="ttdeci">long getCurrPulse() const</div><div class="ttdef"><b>Definition:</b> MotorWheel.cpp:219</div></div>
|
||||
<div class="ttc" id="aclassMotor_html_a55a0ba922517197fd01caac36c84c682"><div class="ttname"><a href="classMotor.html#a55a0ba922517197fd01caac36c84c682">Motor::debugger</a></div><div class="ttdeci">void debugger() const</div><div class="ttdef"><b>Definition:</b> MotorWheel.cpp:240</div></div>
|
||||
<div class="ttc" id="aclassMotor_html_a5e5d272254ecd37a082fc467e9cd2610"><div class="ttname"><a href="classMotor.html#a5e5d272254ecd37a082fc467e9cd2610">Motor::getSpeedPPS</a></div><div class="ttdeci">int getSpeedPPS() const</div><div class="ttdef"><b>Definition:</b> MotorWheel.cpp:216</div></div>
|
||||
<div class="ttc" id="aclassMotor_html_a6358811a51b7636b06199972b7fae417"><div class="ttname"><a href="classMotor.html#a6358811a51b7636b06199972b7fae417">Motor::PIDDisable</a></div><div class="ttdeci">bool PIDDisable()</div><div class="ttdef"><b>Definition:</b> MotorWheel.cpp:159</div></div>
|
||||
<div class="ttc" id="aclassMotor_html_a653642c0cba985a85204fbfe81cf3c8a"><div class="ttname"><a href="classMotor.html#a653642c0cba985a85204fbfe81cf3c8a">Motor::setCurrPulse</a></div><div class="ttdeci">long setCurrPulse(long _pulse)</div><div class="ttdef"><b>Definition:</b> MotorWheel.cpp:222</div></div>
|
||||
<div class="ttc" id="aclassMotor_html_a785eadb656e31e62b1f1515004344ae0"><div class="ttname"><a href="classMotor.html#a785eadb656e31e62b1f1515004344ae0">Motor::getPinIRQ</a></div><div class="ttdeci">unsigned char getPinIRQ() const</div><div class="ttdef"><b>Definition:</b> MotorWheel.cpp:63</div></div>
|
||||
<div class="ttc" id="aclassMotor_html_a826a3f1ffd48fd6f49d74caf7ad68dad"><div class="ttname"><a href="classMotor.html#a826a3f1ffd48fd6f49d74caf7ad68dad">Motor::setupInterrupt</a></div><div class="ttdeci">void setupInterrupt()</div><div class="ttdef"><b>Definition:</b> MotorWheel.cpp:33</div></div>
|
||||
<div class="ttc" id="aclassMotor_html_a8d707212e2395830a9064712df1c4f68"><div class="ttname"><a href="classMotor.html#a8d707212e2395830a9064712df1c4f68">Motor::setSpeedRPM</a></div><div class="ttdeci">unsigned int setSpeedRPM(int speedRPM, bool dir)</div><div class="ttdef"><b>Definition:</b> MotorWheel.cpp:129</div></div>
|
||||
<div class="ttc" id="aclassMotor_html_a9462d1a9af69941100f422ce1a0faeff"><div class="ttname"><a href="classMotor.html#a9462d1a9af69941100f422ce1a0faeff">Motor::setCurrDir</a></div><div class="ttdeci">bool setCurrDir()</div><div class="ttdef"><b>Definition:</b> MotorWheel.cpp:111</div></div>
|
||||
<div class="ttc" id="aclassMotor_html_a9ca625db156da95bc5f4500c294f8e83"><div class="ttname"><a href="classMotor.html#a9ca625db156da95bc5f4500c294f8e83">Motor::PIDGetSpeedRPMDesired</a></div><div class="ttdeci">unsigned int PIDGetSpeedRPMDesired() const</div><div class="ttdef"><b>Definition:</b> MotorWheel.cpp:186</div></div>
|
||||
<div class="ttc" id="aclassMotor_html_aa41934a55ada6dabb95b6741b6d964d3"><div class="ttname"><a href="classMotor.html#aa41934a55ada6dabb95b6741b6d964d3">Motor::getPWM</a></div><div class="ttdeci">unsigned int getPWM() const</div><div class="ttdef"><b>Definition:</b> MotorWheel.cpp:88</div></div>
|
||||
<div class="ttc" id="aclassMotor_html_aa44fc307611e45eeb5e6fb50c79f375b"><div class="ttname"><a href="classMotor.html#aa44fc307611e45eeb5e6fb50c79f375b">Motor::PIDRegulate</a></div><div class="ttdeci">bool PIDRegulate(bool doRegulate=true)</div><div class="ttdef"><b>Definition:</b> MotorWheel.cpp:191</div></div>
|
||||
<div class="ttc" id="aclassMotor_html_aa813d431c39937e90e91f3ad2fbf625d"><div class="ttname"><a href="classMotor.html#aa813d431c39937e90e91f3ad2fbf625d">Motor::getDesiredDir</a></div><div class="ttdeci">bool getDesiredDir() const</div><div class="ttdef"><b>Definition:</b> MotorWheel.cpp:98</div></div>
|
||||
<div class="ttc" id="aclassMotor_html_aaedede5ddae28b6926204dc7a47e0612"><div class="ttname"><a href="classMotor.html#aaedede5ddae28b6926204dc7a47e0612">Motor::getCurrDir</a></div><div class="ttdeci">bool getCurrDir() const</div><div class="ttdef"><b>Definition:</b> MotorWheel.cpp:108</div></div>
|
||||
<div class="ttc" id="aclassMotor_html_acab1e83ffdd286821aa69af770294fae"><div class="ttname"><a href="classMotor.html#acab1e83ffdd286821aa69af770294fae">Motor::isr</a></div><div class="ttdeci">struct ISRVars * isr</div><div class="ttdef"><b>Definition:</b> MotorWheel.h:198</div></div>
|
||||
<div class="ttc" id="aclassMotor_html_ad02c1db58f8f247f4e8becc19d1c7054"><div class="ttname"><a href="classMotor.html#ad02c1db58f8f247f4e8becc19d1c7054">Motor::getPinPWM</a></div><div class="ttdeci">unsigned char getPinPWM() const</div><div class="ttdef"><b>Definition:</b> MotorWheel.cpp:55</div></div>
|
||||
<div class="ttc" id="aclassMotor_html_ad4e09298c4c8b99ab467a4262d8a3207"><div class="ttname"><a href="classMotor.html#ad4e09298c4c8b99ab467a4262d8a3207">Motor::runPWM</a></div><div class="ttdeci">unsigned int runPWM(unsigned int PWM, bool dir, bool saveDir=true)</div><div class="ttdef"><b>Definition:</b> MotorWheel.cpp:72</div></div>
|
||||
<div class="ttc" id="aclassMotor_html_ad6ee53cd8570f60ae5dd83b8604b00fe"><div class="ttname"><a href="classMotor.html#ad6ee53cd8570f60ae5dd83b8604b00fe">Motor::PIDEnable</a></div><div class="ttdeci">bool PIDEnable(float kc=KC, float taui=TAUI, float taud=TAUD, unsigned int sampleTime=1000)</div><div class="ttdef"><b>Definition:</b> MotorWheel.cpp:153</div></div>
|
||||
<div class="ttc" id="aclassMotor_html_ada15a2f02a7945a458b48e829b6a5d6b"><div class="ttname"><a href="classMotor.html#ada15a2f02a7945a458b48e829b6a5d6b">Motor::getSpeedRPM</a></div><div class="ttdeci">int getSpeedRPM() const</div><div class="ttdef"><b>Definition:</b> MotorWheel.cpp:136</div></div>
|
||||
<div class="ttc" id="aclassMotor_html_ae14f43483f26152d92c88aa4c6a7a471"><div class="ttname"><a href="classMotor.html#ae14f43483f26152d92c88aa4c6a7a471">Motor::PIDReset</a></div><div class="ttdeci">bool PIDReset()</div><div class="ttdef"><b>Definition:</b> MotorWheel.cpp:164</div></div>
|
||||
<div class="ttc" id="aclassMotor_html_aeddf9353baeaa0ad9e6de0df5d3e73e8"><div class="ttname"><a href="classMotor.html#aeddf9353baeaa0ad9e6de0df5d3e73e8">Motor::reverseDesiredDir</a></div><div class="ttdeci">bool reverseDesiredDir()</div><div class="ttdef"><b>Definition:</b> MotorWheel.cpp:102</div></div>
|
||||
<div class="ttc" id="aclassMotor_html_aefe7b72985f51315c7ffe81fbf66869c"><div class="ttname"><a href="classMotor.html#aefe7b72985f51315c7ffe81fbf66869c">Motor::backoffPWM</a></div><div class="ttdeci">unsigned int backoffPWM(unsigned int PWM)</div><div class="ttdef"><b>Definition:</b> MotorWheel.cpp:84</div></div>
|
||||
<div class="ttc" id="aclassMotor_html_af085804880a48840dc3d1d088911695e"><div class="ttname"><a href="classMotor.html#af085804880a48840dc3d1d088911695e">Motor::getPinDir</a></div><div class="ttdeci">unsigned char getPinDir() const</div><div class="ttdef"><b>Definition:</b> MotorWheel.cpp:59</div></div>
|
||||
<div class="ttc" id="aclassPID_html"><div class="ttname"><a href="classPID.html">PID</a></div><div class="ttdef"><b>Definition:</b> PID_Beta6.h:5</div></div>
|
||||
<div class="ttc" id="astructISRVars_html"><div class="ttname"><a href="structISRVars.html">ISRVars</a></div><div class="ttdef"><b>Definition:</b> MotorWheel.h:131</div></div>
|
||||
<div class="ttc" id="astructISRVars_html_a24a642bb0d154409a0c7799c6e79552a"><div class="ttname"><a href="structISRVars.html#a24a642bb0d154409a0c7799c6e79552a">ISRVars::pinIRQB</a></div><div class="ttdeci">unsigned char pinIRQB</div><div class="ttdef"><b>Definition:</b> MotorWheel.h:141</div></div>
|
||||
<div class="ttc" id="astructISRVars_html_a38f71602d525494877c66159cf704309"><div class="ttname"><a href="structISRVars.html#a38f71602d525494877c66159cf704309">ISRVars::ISRfunc</a></div><div class="ttdeci">void(* ISRfunc)()</div><div class="ttdef"><b>Definition:</b> MotorWheel.h:132</div></div>
|
||||
<div class="ttc" id="astructISRVars_html_a5fb13f185745e43667ba30d2c0481f74"><div class="ttname"><a href="structISRVars.html#a5fb13f185745e43667ba30d2c0481f74">ISRVars::pulses</a></div><div class="ttdeci">volatile long pulses</div><div class="ttdef"><b>Definition:</b> MotorWheel.h:134</div></div>
|
||||
<div class="ttc" id="astructISRVars_html_a935b7a7cfe9c5a33902ce56256980846"><div class="ttname"><a href="structISRVars.html#a935b7a7cfe9c5a33902ce56256980846">ISRVars::pulseEndMicros</a></div><div class="ttdeci">volatile unsigned long pulseEndMicros</div><div class="ttdef"><b>Definition:</b> MotorWheel.h:136</div></div>
|
||||
<div class="ttc" id="astructISRVars_html_a9db372787f75f20b71f24706af08878e"><div class="ttname"><a href="structISRVars.html#a9db372787f75f20b71f24706af08878e">ISRVars::currDirection</a></div><div class="ttdeci">volatile bool currDirection</div><div class="ttdef"><b>Definition:</b> MotorWheel.h:140</div></div>
|
||||
<div class="ttc" id="astructISRVars_html_aad94840301dc39f51a918b556df8fc11"><div class="ttname"><a href="structISRVars.html#aad94840301dc39f51a918b556df8fc11">ISRVars::pulseStartMicros</a></div><div class="ttdeci">volatile unsigned long pulseStartMicros</div><div class="ttdef"><b>Definition:</b> MotorWheel.h:135</div></div>
|
||||
<div class="ttc" id="astructISRVars_html_ac1eba4ab5f07f4751a050d9cbcedc797"><div class="ttname"><a href="structISRVars.html#ac1eba4ab5f07f4751a050d9cbcedc797">ISRVars::pinIRQ</a></div><div class="ttdeci">unsigned char pinIRQ</div><div class="ttdef"><b>Definition:</b> MotorWheel.h:142</div></div>
|
||||
<div class="ttc" id="astructISRVars_html_af6857712234eae5709feba7c699e0ac7"><div class="ttname"><a href="structISRVars.html#af6857712234eae5709feba7c699e0ac7">ISRVars::speedPPS</a></div><div class="ttdeci">volatile unsigned int speedPPS</div><div class="ttdef"><b>Definition:</b> MotorWheel.h:137</div></div>
|
||||
</div><!-- fragment --></div><!-- contents -->
|
||||
<!-- start footer part -->
|
||||
<hr class="footer"/><address class="footer"><small>
|
||||
Generated by <a href="https://www.doxygen.org/index.html"><img class="footer" src="doxygen.svg" width="104" height="31" alt="doxygen"/></a> 1.9.1
|
||||
</small></address>
|
||||
</body>
|
||||
</html>
|
@ -1,97 +0,0 @@
|
||||
<!DOCTYPE html PUBLIC "-//W3C//DTD XHTML 1.0 Transitional//EN" "https://www.w3.org/TR/xhtml1/DTD/xhtml1-transitional.dtd">
|
||||
<html xmlns="http://www.w3.org/1999/xhtml">
|
||||
<head>
|
||||
<meta http-equiv="Content-Type" content="text/xhtml;charset=UTF-8"/>
|
||||
<meta http-equiv="X-UA-Compatible" content="IE=9"/>
|
||||
<meta name="generator" content="Doxygen 1.9.1"/>
|
||||
<meta name="viewport" content="width=device-width, initial-scale=1"/>
|
||||
<title>DCAITI Robot Hardware: lib/PID_Beta6/PID_Beta6.cpp File Reference</title>
|
||||
<link href="tabs.css" rel="stylesheet" type="text/css"/>
|
||||
<script type="text/javascript" src="jquery.js"></script>
|
||||
<script type="text/javascript" src="dynsections.js"></script>
|
||||
<link href="search/search.css" rel="stylesheet" type="text/css"/>
|
||||
<script type="text/javascript" src="search/searchdata.js"></script>
|
||||
<script type="text/javascript" src="search/search.js"></script>
|
||||
<link href="doxygen.css" rel="stylesheet" type="text/css" />
|
||||
</head>
|
||||
<body>
|
||||
<div id="top"><!-- do not remove this div, it is closed by doxygen! -->
|
||||
<div id="titlearea">
|
||||
<table cellspacing="0" cellpadding="0">
|
||||
<tbody>
|
||||
<tr style="height: 56px;">
|
||||
<td id="projectalign" style="padding-left: 0.5em;">
|
||||
<div id="projectname">DCAITI Robot Hardware
|
||||
 <span id="projectnumber">1.0</span>
|
||||
</div>
|
||||
</td>
|
||||
</tr>
|
||||
</tbody>
|
||||
</table>
|
||||
</div>
|
||||
<!-- end header part -->
|
||||
<!-- Generated by Doxygen 1.9.1 -->
|
||||
<script type="text/javascript">
|
||||
/* @license magnet:?xt=urn:btih:cf05388f2679ee054f2beb29a391d25f4e673ac3&dn=gpl-2.0.txt GPL-v2 */
|
||||
var searchBox = new SearchBox("searchBox", "search",false,'Search','.html');
|
||||
/* @license-end */
|
||||
</script>
|
||||
<script type="text/javascript" src="menudata.js"></script>
|
||||
<script type="text/javascript" src="menu.js"></script>
|
||||
<script type="text/javascript">
|
||||
/* @license magnet:?xt=urn:btih:cf05388f2679ee054f2beb29a391d25f4e673ac3&dn=gpl-2.0.txt GPL-v2 */
|
||||
$(function() {
|
||||
initMenu('',true,false,'search.php','Search');
|
||||
$(document).ready(function() { init_search(); });
|
||||
});
|
||||
/* @license-end */</script>
|
||||
<div id="main-nav"></div>
|
||||
<!-- window showing the filter options -->
|
||||
<div id="MSearchSelectWindow"
|
||||
onmouseover="return searchBox.OnSearchSelectShow()"
|
||||
onmouseout="return searchBox.OnSearchSelectHide()"
|
||||
onkeydown="return searchBox.OnSearchSelectKey(event)">
|
||||
</div>
|
||||
|
||||
<!-- iframe showing the search results (closed by default) -->
|
||||
<div id="MSearchResultsWindow">
|
||||
<iframe src="javascript:void(0)" frameborder="0"
|
||||
name="MSearchResults" id="MSearchResults">
|
||||
</iframe>
|
||||
</div>
|
||||
|
||||
<div id="nav-path" class="navpath">
|
||||
<ul>
|
||||
<li class="navelem"><a class="el" href="dir_97aefd0d527b934f1d99a682da8fe6a9.html">lib</a></li><li class="navelem"><a class="el" href="dir_20ba189d08eafd7afd9a71ede3a1ee33.html">PID_Beta6</a></li> </ul>
|
||||
</div>
|
||||
</div><!-- top -->
|
||||
<div class="header">
|
||||
<div class="headertitle">
|
||||
<div class="title">PID_Beta6.cpp File Reference</div> </div>
|
||||
</div><!--header-->
|
||||
<div class="contents">
|
||||
<div class="textblock"><code>#include "wiring.h"</code><br />
|
||||
<code>#include <<a class="el" href="PID__Beta6_8h_source.html">PID_Beta6.h</a>></code><br />
|
||||
<code>#include "<a class="el" href="fuzzy__table_8h_source.html">fuzzy_table.h</a>"</code><br />
|
||||
<code>#include <wiring_private.h></code><br />
|
||||
<code>#include <HardwareSerial.h></code><br />
|
||||
</div><div class="textblock"><div class="dynheader">
|
||||
Include dependency graph for PID_Beta6.cpp:</div>
|
||||
<div class="dyncontent">
|
||||
<div class="center"><img src="PID__Beta6_8cpp__incl.png" border="0" usemap="#alib_2PID__Beta6_2PID__Beta6_8cpp" alt=""/></div>
|
||||
<map name="alib_2PID__Beta6_2PID__Beta6_8cpp" id="alib_2PID__Beta6_2PID__Beta6_8cpp">
|
||||
<area shape="rect" title=" " alt="" coords="181,5,387,32"/>
|
||||
<area shape="rect" title=" " alt="" coords="5,80,80,107"/>
|
||||
<area shape="rect" href="PID__Beta6_8h.html" title=" " alt="" coords="104,80,205,107"/>
|
||||
<area shape="rect" href="fuzzy__table_8h.html" title=" " alt="" coords="229,80,339,107"/>
|
||||
<area shape="rect" title=" " alt="" coords="363,80,490,107"/>
|
||||
<area shape="rect" title=" " alt="" coords="514,80,649,107"/>
|
||||
</map>
|
||||
</div>
|
||||
</div></div><!-- contents -->
|
||||
<!-- start footer part -->
|
||||
<hr class="footer"/><address class="footer"><small>
|
||||
Generated by <a href="https://www.doxygen.org/index.html"><img class="footer" src="doxygen.svg" width="104" height="31" alt="doxygen"/></a> 1.9.1
|
||||
</small></address>
|
||||
</body>
|
||||
</html>
|
@ -1,8 +0,0 @@
|
||||
<map id="lib/PID_Beta6/PID_Beta6.cpp" name="lib/PID_Beta6/PID_Beta6.cpp">
|
||||
<area shape="rect" id="node1" title=" " alt="" coords="181,5,387,32"/>
|
||||
<area shape="rect" id="node2" title=" " alt="" coords="5,80,80,107"/>
|
||||
<area shape="rect" id="node3" href="$PID__Beta6_8h.html" title=" " alt="" coords="104,80,205,107"/>
|
||||
<area shape="rect" id="node4" href="$fuzzy__table_8h.html" title=" " alt="" coords="229,80,339,107"/>
|
||||
<area shape="rect" id="node5" title=" " alt="" coords="363,80,490,107"/>
|
||||
<area shape="rect" id="node6" title=" " alt="" coords="514,80,649,107"/>
|
||||
</map>
|
@ -1 +0,0 @@
|
||||
0c460ef1d1cb18681c87d46c2e51bab2
|
Before Width: | Height: | Size: 12 KiB |
@ -1,156 +0,0 @@
|
||||
<!DOCTYPE html PUBLIC "-//W3C//DTD XHTML 1.0 Transitional//EN" "https://www.w3.org/TR/xhtml1/DTD/xhtml1-transitional.dtd">
|
||||
<html xmlns="http://www.w3.org/1999/xhtml">
|
||||
<head>
|
||||
<meta http-equiv="Content-Type" content="text/xhtml;charset=UTF-8"/>
|
||||
<meta http-equiv="X-UA-Compatible" content="IE=9"/>
|
||||
<meta name="generator" content="Doxygen 1.9.1"/>
|
||||
<meta name="viewport" content="width=device-width, initial-scale=1"/>
|
||||
<title>DCAITI Robot Hardware: lib/PID_Beta6/PID_Beta6.h File Reference</title>
|
||||
<link href="tabs.css" rel="stylesheet" type="text/css"/>
|
||||
<script type="text/javascript" src="jquery.js"></script>
|
||||
<script type="text/javascript" src="dynsections.js"></script>
|
||||
<link href="search/search.css" rel="stylesheet" type="text/css"/>
|
||||
<script type="text/javascript" src="search/searchdata.js"></script>
|
||||
<script type="text/javascript" src="search/search.js"></script>
|
||||
<link href="doxygen.css" rel="stylesheet" type="text/css" />
|
||||
</head>
|
||||
<body>
|
||||
<div id="top"><!-- do not remove this div, it is closed by doxygen! -->
|
||||
<div id="titlearea">
|
||||
<table cellspacing="0" cellpadding="0">
|
||||
<tbody>
|
||||
<tr style="height: 56px;">
|
||||
<td id="projectalign" style="padding-left: 0.5em;">
|
||||
<div id="projectname">DCAITI Robot Hardware
|
||||
 <span id="projectnumber">1.0</span>
|
||||
</div>
|
||||
</td>
|
||||
</tr>
|
||||
</tbody>
|
||||
</table>
|
||||
</div>
|
||||
<!-- end header part -->
|
||||
<!-- Generated by Doxygen 1.9.1 -->
|
||||
<script type="text/javascript">
|
||||
/* @license magnet:?xt=urn:btih:cf05388f2679ee054f2beb29a391d25f4e673ac3&dn=gpl-2.0.txt GPL-v2 */
|
||||
var searchBox = new SearchBox("searchBox", "search",false,'Search','.html');
|
||||
/* @license-end */
|
||||
</script>
|
||||
<script type="text/javascript" src="menudata.js"></script>
|
||||
<script type="text/javascript" src="menu.js"></script>
|
||||
<script type="text/javascript">
|
||||
/* @license magnet:?xt=urn:btih:cf05388f2679ee054f2beb29a391d25f4e673ac3&dn=gpl-2.0.txt GPL-v2 */
|
||||
$(function() {
|
||||
initMenu('',true,false,'search.php','Search');
|
||||
$(document).ready(function() { init_search(); });
|
||||
});
|
||||
/* @license-end */</script>
|
||||
<div id="main-nav"></div>
|
||||
<!-- window showing the filter options -->
|
||||
<div id="MSearchSelectWindow"
|
||||
onmouseover="return searchBox.OnSearchSelectShow()"
|
||||
onmouseout="return searchBox.OnSearchSelectHide()"
|
||||
onkeydown="return searchBox.OnSearchSelectKey(event)">
|
||||
</div>
|
||||
|
||||
<!-- iframe showing the search results (closed by default) -->
|
||||
<div id="MSearchResultsWindow">
|
||||
<iframe src="javascript:void(0)" frameborder="0"
|
||||
name="MSearchResults" id="MSearchResults">
|
||||
</iframe>
|
||||
</div>
|
||||
|
||||
<div id="nav-path" class="navpath">
|
||||
<ul>
|
||||
<li class="navelem"><a class="el" href="dir_97aefd0d527b934f1d99a682da8fe6a9.html">lib</a></li><li class="navelem"><a class="el" href="dir_20ba189d08eafd7afd9a71ede3a1ee33.html">PID_Beta6</a></li> </ul>
|
||||
</div>
|
||||
</div><!-- top -->
|
||||
<div class="header">
|
||||
<div class="summary">
|
||||
<a href="#nested-classes">Classes</a> |
|
||||
<a href="#define-members">Macros</a> </div>
|
||||
<div class="headertitle">
|
||||
<div class="title">PID_Beta6.h File Reference</div> </div>
|
||||
</div><!--header-->
|
||||
<div class="contents">
|
||||
<div class="textblock"><div class="dynheader">
|
||||
This graph shows which files directly or indirectly include this file:</div>
|
||||
<div class="dyncontent">
|
||||
<div class="center"><img src="PID__Beta6_8h__dep__incl.png" border="0" usemap="#alib_2PID__Beta6_2PID__Beta6_8hdep" alt=""/></div>
|
||||
<map name="alib_2PID__Beta6_2PID__Beta6_8hdep" id="alib_2PID__Beta6_2PID__Beta6_8hdep">
|
||||
<area shape="rect" title=" " alt="" coords="161,5,353,32"/>
|
||||
<area shape="rect" href="main_8cpp.html" title=" " alt="" coords="5,155,111,181"/>
|
||||
<area shape="rect" href="MotorWheel_8h.html" title=" " alt="" coords="149,80,365,107"/>
|
||||
<area shape="rect" href="PID__Beta6_8cpp.html" title=" " alt="" coords="389,80,596,107"/>
|
||||
<area shape="rect" href="UARTCom_8cpp.html" title=" " alt="" coords="135,155,378,181"/>
|
||||
<area shape="rect" href="UCommands_8cpp.html" title=" " alt="" coords="402,155,663,181"/>
|
||||
<area shape="rect" href="MotorWheel_8cpp.html" title=" " alt="" coords="688,155,919,181"/>
|
||||
</map>
|
||||
</div>
|
||||
</div>
|
||||
<p><a href="PID__Beta6_8h_source.html">Go to the source code of this file.</a></p>
|
||||
<table class="memberdecls">
|
||||
<tr class="heading"><td colspan="2"><h2 class="groupheader"><a name="nested-classes"></a>
|
||||
Classes</h2></td></tr>
|
||||
<tr class="memitem:"><td class="memItemLeft" align="right" valign="top">class  </td><td class="memItemRight" valign="bottom"><a class="el" href="classPID.html">PID</a></td></tr>
|
||||
<tr class="separator:"><td class="memSeparator" colspan="2"> </td></tr>
|
||||
</table><table class="memberdecls">
|
||||
<tr class="heading"><td colspan="2"><h2 class="groupheader"><a name="define-members"></a>
|
||||
Macros</h2></td></tr>
|
||||
<tr class="memitem:a0cc6f7717df9fbdc0f33efb88720a639"><td class="memItemLeft" align="right" valign="top">#define </td><td class="memItemRight" valign="bottom"><a class="el" href="PID__Beta6_8h.html#a0cc6f7717df9fbdc0f33efb88720a639">AUTO</a>   1</td></tr>
|
||||
<tr class="separator:a0cc6f7717df9fbdc0f33efb88720a639"><td class="memSeparator" colspan="2"> </td></tr>
|
||||
<tr class="memitem:a8187a9af791c0a44ba67edd9cf266961"><td class="memItemLeft" align="right" valign="top">#define </td><td class="memItemRight" valign="bottom"><a class="el" href="PID__Beta6_8h.html#a8187a9af791c0a44ba67edd9cf266961">MANUAL</a>   0</td></tr>
|
||||
<tr class="separator:a8187a9af791c0a44ba67edd9cf266961"><td class="memSeparator" colspan="2"> </td></tr>
|
||||
<tr class="memitem:a8650e6793d46032c617bb7b824f90bfd"><td class="memItemLeft" align="right" valign="top">#define </td><td class="memItemRight" valign="bottom"><a class="el" href="PID__Beta6_8h.html#a8650e6793d46032c617bb7b824f90bfd">LIBRARY_VERSION</a>   0.6</td></tr>
|
||||
<tr class="separator:a8650e6793d46032c617bb7b824f90bfd"><td class="memSeparator" colspan="2"> </td></tr>
|
||||
</table>
|
||||
<h2 class="groupheader">Macro Definition Documentation</h2>
|
||||
<a id="a0cc6f7717df9fbdc0f33efb88720a639"></a>
|
||||
<h2 class="memtitle"><span class="permalink"><a href="#a0cc6f7717df9fbdc0f33efb88720a639">◆ </a></span>AUTO</h2>
|
||||
|
||||
<div class="memitem">
|
||||
<div class="memproto">
|
||||
<table class="memname">
|
||||
<tr>
|
||||
<td class="memname">#define AUTO   1</td>
|
||||
</tr>
|
||||
</table>
|
||||
</div><div class="memdoc">
|
||||
|
||||
</div>
|
||||
</div>
|
||||
<a id="a8650e6793d46032c617bb7b824f90bfd"></a>
|
||||
<h2 class="memtitle"><span class="permalink"><a href="#a8650e6793d46032c617bb7b824f90bfd">◆ </a></span>LIBRARY_VERSION</h2>
|
||||
|
||||
<div class="memitem">
|
||||
<div class="memproto">
|
||||
<table class="memname">
|
||||
<tr>
|
||||
<td class="memname">#define LIBRARY_VERSION   0.6</td>
|
||||
</tr>
|
||||
</table>
|
||||
</div><div class="memdoc">
|
||||
|
||||
</div>
|
||||
</div>
|
||||
<a id="a8187a9af791c0a44ba67edd9cf266961"></a>
|
||||
<h2 class="memtitle"><span class="permalink"><a href="#a8187a9af791c0a44ba67edd9cf266961">◆ </a></span>MANUAL</h2>
|
||||
|
||||
<div class="memitem">
|
||||
<div class="memproto">
|
||||
<table class="memname">
|
||||
<tr>
|
||||
<td class="memname">#define MANUAL   0</td>
|
||||
</tr>
|
||||
</table>
|
||||
</div><div class="memdoc">
|
||||
|
||||
</div>
|
||||
</div>
|
||||
</div><!-- contents -->
|
||||
<!-- start footer part -->
|
||||
<hr class="footer"/><address class="footer"><small>
|
||||
Generated by <a href="https://www.doxygen.org/index.html"><img class="footer" src="doxygen.svg" width="104" height="31" alt="doxygen"/></a> 1.9.1
|
||||
</small></address>
|
||||
</body>
|
||||
</html>
|
@ -1,9 +0,0 @@
|
||||
<map id="lib/PID_Beta6/PID_Beta6.h" name="lib/PID_Beta6/PID_Beta6.h">
|
||||
<area shape="rect" id="node1" title=" " alt="" coords="161,5,353,32"/>
|
||||
<area shape="rect" id="node2" href="$main_8cpp.html" title=" " alt="" coords="5,155,111,181"/>
|
||||
<area shape="rect" id="node3" href="$MotorWheel_8h.html" title=" " alt="" coords="149,80,365,107"/>
|
||||
<area shape="rect" id="node7" href="$PID__Beta6_8cpp.html" title=" " alt="" coords="389,80,596,107"/>
|
||||
<area shape="rect" id="node4" href="$UARTCom_8cpp.html" title=" " alt="" coords="135,155,378,181"/>
|
||||
<area shape="rect" id="node5" href="$UCommands_8cpp.html" title=" " alt="" coords="402,155,663,181"/>
|
||||
<area shape="rect" id="node6" href="$MotorWheel_8cpp.html" title=" " alt="" coords="688,155,919,181"/>
|
||||
</map>
|
@ -1 +0,0 @@
|
||||
f7db92b5c31d72b4df9da6bff5d0ab7f
|
Before Width: | Height: | Size: 19 KiB |
@ -1,211 +0,0 @@
|
||||
<!DOCTYPE html PUBLIC "-//W3C//DTD XHTML 1.0 Transitional//EN" "https://www.w3.org/TR/xhtml1/DTD/xhtml1-transitional.dtd">
|
||||
<html xmlns="http://www.w3.org/1999/xhtml">
|
||||
<head>
|
||||
<meta http-equiv="Content-Type" content="text/xhtml;charset=UTF-8"/>
|
||||
<meta http-equiv="X-UA-Compatible" content="IE=9"/>
|
||||
<meta name="generator" content="Doxygen 1.9.1"/>
|
||||
<meta name="viewport" content="width=device-width, initial-scale=1"/>
|
||||
<title>DCAITI Robot Hardware: lib/PID_Beta6/PID_Beta6.h Source File</title>
|
||||
<link href="tabs.css" rel="stylesheet" type="text/css"/>
|
||||
<script type="text/javascript" src="jquery.js"></script>
|
||||
<script type="text/javascript" src="dynsections.js"></script>
|
||||
<link href="search/search.css" rel="stylesheet" type="text/css"/>
|
||||
<script type="text/javascript" src="search/searchdata.js"></script>
|
||||
<script type="text/javascript" src="search/search.js"></script>
|
||||
<link href="doxygen.css" rel="stylesheet" type="text/css" />
|
||||
</head>
|
||||
<body>
|
||||
<div id="top"><!-- do not remove this div, it is closed by doxygen! -->
|
||||
<div id="titlearea">
|
||||
<table cellspacing="0" cellpadding="0">
|
||||
<tbody>
|
||||
<tr style="height: 56px;">
|
||||
<td id="projectalign" style="padding-left: 0.5em;">
|
||||
<div id="projectname">DCAITI Robot Hardware
|
||||
 <span id="projectnumber">1.0</span>
|
||||
</div>
|
||||
</td>
|
||||
</tr>
|
||||
</tbody>
|
||||
</table>
|
||||
</div>
|
||||
<!-- end header part -->
|
||||
<!-- Generated by Doxygen 1.9.1 -->
|
||||
<script type="text/javascript">
|
||||
/* @license magnet:?xt=urn:btih:cf05388f2679ee054f2beb29a391d25f4e673ac3&dn=gpl-2.0.txt GPL-v2 */
|
||||
var searchBox = new SearchBox("searchBox", "search",false,'Search','.html');
|
||||
/* @license-end */
|
||||
</script>
|
||||
<script type="text/javascript" src="menudata.js"></script>
|
||||
<script type="text/javascript" src="menu.js"></script>
|
||||
<script type="text/javascript">
|
||||
/* @license magnet:?xt=urn:btih:cf05388f2679ee054f2beb29a391d25f4e673ac3&dn=gpl-2.0.txt GPL-v2 */
|
||||
$(function() {
|
||||
initMenu('',true,false,'search.php','Search');
|
||||
$(document).ready(function() { init_search(); });
|
||||
});
|
||||
/* @license-end */</script>
|
||||
<div id="main-nav"></div>
|
||||
<!-- window showing the filter options -->
|
||||
<div id="MSearchSelectWindow"
|
||||
onmouseover="return searchBox.OnSearchSelectShow()"
|
||||
onmouseout="return searchBox.OnSearchSelectHide()"
|
||||
onkeydown="return searchBox.OnSearchSelectKey(event)">
|
||||
</div>
|
||||
|
||||
<!-- iframe showing the search results (closed by default) -->
|
||||
<div id="MSearchResultsWindow">
|
||||
<iframe src="javascript:void(0)" frameborder="0"
|
||||
name="MSearchResults" id="MSearchResults">
|
||||
</iframe>
|
||||
</div>
|
||||
|
||||
<div id="nav-path" class="navpath">
|
||||
<ul>
|
||||
<li class="navelem"><a class="el" href="dir_97aefd0d527b934f1d99a682da8fe6a9.html">lib</a></li><li class="navelem"><a class="el" href="dir_20ba189d08eafd7afd9a71ede3a1ee33.html">PID_Beta6</a></li> </ul>
|
||||
</div>
|
||||
</div><!-- top -->
|
||||
<div class="header">
|
||||
<div class="headertitle">
|
||||
<div class="title">PID_Beta6.h</div> </div>
|
||||
</div><!--header-->
|
||||
<div class="contents">
|
||||
<a href="PID__Beta6_8h.html">Go to the documentation of this file.</a><div class="fragment"><div class="line"><a name="l00001"></a><span class="lineno"> 1</span> <span class="preprocessor">#ifndef PID_Beta6_h</span></div>
|
||||
<div class="line"><a name="l00002"></a><span class="lineno"> 2</span> <span class="preprocessor">#define PID_Beta6_h</span></div>
|
||||
<div class="line"><a name="l00003"></a><span class="lineno"> 3</span>  </div>
|
||||
<div class="line"><a name="l00004"></a><span class="lineno"><a class="line" href="classPID.html"> 4</a></span> <span class="keyword">class </span><a class="code" href="classPID.html">PID</a></div>
|
||||
<div class="line"><a name="l00005"></a><span class="lineno"> 5</span> {</div>
|
||||
<div class="line"><a name="l00006"></a><span class="lineno"> 6</span>  </div>
|
||||
<div class="line"><a name="l00007"></a><span class="lineno"> 7</span>  </div>
|
||||
<div class="line"><a name="l00008"></a><span class="lineno"> 8</span>  <span class="keyword">public</span>:</div>
|
||||
<div class="line"><a name="l00009"></a><span class="lineno"> 9</span>  </div>
|
||||
<div class="line"><a name="l00010"></a><span class="lineno"><a class="line" href="PID__Beta6_8h.html#a0cc6f7717df9fbdc0f33efb88720a639"> 10</a></span> <span class="preprocessor"> #define AUTO 1</span></div>
|
||||
<div class="line"><a name="l00011"></a><span class="lineno"><a class="line" href="PID__Beta6_8h.html#a8187a9af791c0a44ba67edd9cf266961"> 11</a></span> <span class="preprocessor"> #define MANUAL 0</span></div>
|
||||
<div class="line"><a name="l00012"></a><span class="lineno"><a class="line" href="PID__Beta6_8h.html#a8650e6793d46032c617bb7b824f90bfd"> 12</a></span> <span class="preprocessor"> #define LIBRARY_VERSION 0.6</span></div>
|
||||
<div class="line"><a name="l00013"></a><span class="lineno"> 13</span>  </div>
|
||||
<div class="line"><a name="l00014"></a><span class="lineno"> 14</span>  <span class="comment">//commonly used functions **************************************************************************</span></div>
|
||||
<div class="line"><a name="l00015"></a><span class="lineno"> 15</span>  <a class="code" href="classPID.html#a70a457a8b2d0f2306923c30282567af6">PID</a>(<span class="keywordtype">int</span>*, <span class="keywordtype">int</span>*, <span class="keywordtype">int</span>*, <span class="comment">// * constructor. links the PID to the Input, Output, and </span></div>
|
||||
<div class="line"><a name="l00016"></a><span class="lineno"> 16</span>  <span class="keywordtype">float</span>, <span class="keywordtype">float</span>, <span class="keywordtype">float</span>); <span class="comment">// Setpoint. Initial tuning parameters are also set here</span></div>
|
||||
<div class="line"><a name="l00017"></a><span class="lineno"> 17</span>  </div>
|
||||
<div class="line"><a name="l00018"></a><span class="lineno"> 18</span>  <a class="code" href="classPID.html#a70a457a8b2d0f2306923c30282567af6">PID</a>(<span class="keywordtype">int</span>*, <span class="keywordtype">int</span>*, <span class="keywordtype">int</span>*, <span class="comment">// * Overloaded Constructor. if the user wants to implement</span></div>
|
||||
<div class="line"><a name="l00019"></a><span class="lineno"> 19</span>  <span class="keywordtype">int</span>*, <span class="keywordtype">float</span>, <span class="keywordtype">float</span>, <span class="keywordtype">float</span>); <span class="comment">// feed-forward</span></div>
|
||||
<div class="line"><a name="l00020"></a><span class="lineno"> 20</span>  </div>
|
||||
<div class="line"><a name="l00021"></a><span class="lineno"> 21</span>  <span class="keywordtype">void</span> <a class="code" href="classPID.html#a68074bad88a8cc442ee03a036073d5d5">SetMode</a>(<span class="keywordtype">int</span> Mode); <span class="comment">// * sets PID to either Manual (0) or Auto (non-0)</span></div>
|
||||
<div class="line"><a name="l00022"></a><span class="lineno"> 22</span>  </div>
|
||||
<div class="line"><a name="l00023"></a><span class="lineno"> 23</span>  <span class="keywordtype">void</span> <a class="code" href="classPID.html#a05a3258d4b553e7a121f7360ffe88065">Compute</a>(); <span class="comment">// * performs the PID calculation. it should be</span></div>
|
||||
<div class="line"><a name="l00024"></a><span class="lineno"> 24</span>  <span class="comment">// called every time loop() cycles. ON/OFF and</span></div>
|
||||
<div class="line"><a name="l00025"></a><span class="lineno"> 25</span>  <span class="comment">// calculation frequency can be set using SetMode</span></div>
|
||||
<div class="line"><a name="l00026"></a><span class="lineno"> 26</span>  <span class="comment">// SetSampleTime respectively</span></div>
|
||||
<div class="line"><a name="l00027"></a><span class="lineno"> 27</span>  </div>
|
||||
<div class="line"><a name="l00028"></a><span class="lineno"> 28</span>  <span class="keywordtype">void</span> <a class="code" href="classPID.html#aa84bd27695ea7b6f80a0a6170abb410f">SetInputLimits</a>(<span class="keywordtype">int</span>, <span class="keywordtype">int</span>); <span class="comment">//Tells the PID what 0-100% are for the Input</span></div>
|
||||
<div class="line"><a name="l00029"></a><span class="lineno"> 29</span>  </div>
|
||||
<div class="line"><a name="l00030"></a><span class="lineno"> 30</span>  <span class="keywordtype">void</span> <a class="code" href="classPID.html#a7a1fbe9bbf606557cef3fcf07f04d3f6">SetOutputLimits</a>(<span class="keywordtype">int</span>, <span class="keywordtype">int</span>); <span class="comment">//Tells the PID what 0-100% are for the Output</span></div>
|
||||
<div class="line"><a name="l00031"></a><span class="lineno"> 31</span>  </div>
|
||||
<div class="line"><a name="l00032"></a><span class="lineno"> 32</span>  </div>
|
||||
<div class="line"><a name="l00033"></a><span class="lineno"> 33</span>  <span class="comment">//available but not commonly used functions ********************************************************</span></div>
|
||||
<div class="line"><a name="l00034"></a><span class="lineno"> 34</span>  <span class="keywordtype">void</span> <a class="code" href="classPID.html#aa51d6ef0803413fd0da475406a5ae6ad">SetTunings</a>(<span class="keywordtype">float</span>, <span class="keywordtype">float</span>, <span class="comment">// * While most users will set the tunings once in the </span></div>
|
||||
<div class="line"><a name="l00035"></a><span class="lineno"> 35</span>  <span class="keywordtype">float</span>); <span class="comment">// constructor, this function gives the user the option</span></div>
|
||||
<div class="line"><a name="l00036"></a><span class="lineno"> 36</span>  <span class="comment">// of changing tunings during runtime for Adaptive control</span></div>
|
||||
<div class="line"><a name="l00037"></a><span class="lineno"> 37</span>  </div>
|
||||
<div class="line"><a name="l00038"></a><span class="lineno"> 38</span>  <span class="keywordtype">void</span> <a class="code" href="classPID.html#aaa1e0e67a0c97571bd62b326e6cf3b2e">SetSampleTime</a>(<span class="keywordtype">int</span>); <span class="comment">// * sets the frequency, in Milliseconds, with which </span></div>
|
||||
<div class="line"><a name="l00039"></a><span class="lineno"> 39</span>  <span class="comment">// the PID calculation is performed. default is 1000 </span></div>
|
||||
<div class="line"><a name="l00040"></a><span class="lineno"> 40</span>  </div>
|
||||
<div class="line"><a name="l00041"></a><span class="lineno"> 41</span>  <span class="keywordtype">void</span> <a class="code" href="classPID.html#a9f949fd4445477ee9bf1af2bfa3e1a84">Reset</a>(); <span class="comment">// * reinitializes controller internals. automatically</span></div>
|
||||
<div class="line"><a name="l00042"></a><span class="lineno"> 42</span>  <span class="comment">// called on a manual to auto transition</span></div>
|
||||
<div class="line"><a name="l00043"></a><span class="lineno"> 43</span>  </div>
|
||||
<div class="line"><a name="l00044"></a><span class="lineno"> 44</span>  <span class="keywordtype">bool</span> <a class="code" href="classPID.html#a34178c5110d89a8029e403f6ef5d003d">JustCalculated</a>(); <span class="comment">// * in certain situations, it helps to know when the PID has</span></div>
|
||||
<div class="line"><a name="l00045"></a><span class="lineno"> 45</span>  <span class="comment">// computed this bit will be true for one cycle after the</span></div>
|
||||
<div class="line"><a name="l00046"></a><span class="lineno"> 46</span>  <span class="comment">// pid calculation has occurred</span></div>
|
||||
<div class="line"><a name="l00047"></a><span class="lineno"> 47</span>  </div>
|
||||
<div class="line"><a name="l00048"></a><span class="lineno"> 48</span>  </div>
|
||||
<div class="line"><a name="l00049"></a><span class="lineno"> 49</span>  <span class="comment">//Status functions allow you to query current PID constants ***************************************</span></div>
|
||||
<div class="line"><a name="l00050"></a><span class="lineno"> 50</span>  <span class="keywordtype">int</span> <a class="code" href="classPID.html#acc325db5e6a140b92c8199a66e03491b">GetMode</a>();</div>
|
||||
<div class="line"><a name="l00051"></a><span class="lineno"> 51</span>  <span class="keywordtype">int</span> <a class="code" href="classPID.html#a7c6fb1d00b7ceb89f833c85a10425a99">GetINMin</a>();</div>
|
||||
<div class="line"><a name="l00052"></a><span class="lineno"> 52</span>  <span class="keywordtype">int</span> <a class="code" href="classPID.html#aada1bd2d75fc4cfb8d4e8b3bb7d6efb3">GetINMax</a>();</div>
|
||||
<div class="line"><a name="l00053"></a><span class="lineno"> 53</span>  <span class="keywordtype">int</span> <a class="code" href="classPID.html#a3d18162a81fab3b59b66f2398c2f55da">GetOUTMin</a>();</div>
|
||||
<div class="line"><a name="l00054"></a><span class="lineno"> 54</span>  <span class="keywordtype">int</span> <a class="code" href="classPID.html#afca76f72062cde15b4d738b693215bf6">GetOUTMax</a>();</div>
|
||||
<div class="line"><a name="l00055"></a><span class="lineno"> 55</span>  <span class="keywordtype">int</span> <a class="code" href="classPID.html#aefa4318e7ab26fbdfd7a2f6870d694e8">GetSampleTime</a>();</div>
|
||||
<div class="line"><a name="l00056"></a><span class="lineno"> 56</span>  <span class="keywordtype">float</span> <a class="code" href="classPID.html#a44a5a23e5ab0ebc59ac56cd6e63a74e9">GetP_Param</a>();</div>
|
||||
<div class="line"><a name="l00057"></a><span class="lineno"> 57</span>  <span class="keywordtype">float</span> <a class="code" href="classPID.html#a5dcf844aec5142d13f0e1a9af2eac237">GetI_Param</a>();</div>
|
||||
<div class="line"><a name="l00058"></a><span class="lineno"> 58</span>  <span class="keywordtype">float</span> <a class="code" href="classPID.html#a752d07a63dd8d90191a28d24ea85861c">GetD_Param</a>();</div>
|
||||
<div class="line"><a name="l00059"></a><span class="lineno"> 59</span>  </div>
|
||||
<div class="line"><a name="l00060"></a><span class="lineno"> 60</span>  </div>
|
||||
<div class="line"><a name="l00061"></a><span class="lineno"> 61</span>  <span class="keyword">private</span>:</div>
|
||||
<div class="line"><a name="l00062"></a><span class="lineno"> 62</span>  </div>
|
||||
<div class="line"><a name="l00063"></a><span class="lineno"> 63</span>  <span class="keywordtype">void</span> ConstructorCommon(<span class="keywordtype">int</span>*, <span class="keywordtype">int</span>*, <span class="keywordtype">int</span>*, <span class="comment">// * code that is shared by the constructors</span></div>
|
||||
<div class="line"><a name="l00064"></a><span class="lineno"> 64</span>  <span class="keywordtype">float</span>, <span class="keywordtype">float</span>, <span class="keywordtype">float</span>);</div>
|
||||
<div class="line"><a name="l00065"></a><span class="lineno"> 65</span>  </div>
|
||||
<div class="line"><a name="l00066"></a><span class="lineno"> 66</span>  <span class="comment">//scaled, tweaked parameters we'll actually be using</span></div>
|
||||
<div class="line"><a name="l00067"></a><span class="lineno"> 67</span>  <span class="keywordtype">float</span> kc; <span class="comment">// * (P)roportional Tuning Parameter</span></div>
|
||||
<div class="line"><a name="l00068"></a><span class="lineno"> 68</span>  <span class="keywordtype">float</span> taur; <span class="comment">// * (I)ntegral Tuning Parameter</span></div>
|
||||
<div class="line"><a name="l00069"></a><span class="lineno"> 69</span>  <span class="keywordtype">float</span> taud; <span class="comment">// * (D)erivative Tuning Parameter</span></div>
|
||||
<div class="line"><a name="l00070"></a><span class="lineno"> 70</span>  </div>
|
||||
<div class="line"><a name="l00071"></a><span class="lineno"> 71</span>  <span class="keywordtype">float</span> cof_A;</div>
|
||||
<div class="line"><a name="l00072"></a><span class="lineno"> 72</span>  <span class="keywordtype">float</span> cof_B;</div>
|
||||
<div class="line"><a name="l00073"></a><span class="lineno"> 73</span>  <span class="keywordtype">float</span> cof_C;</div>
|
||||
<div class="line"><a name="l00074"></a><span class="lineno"> 74</span>  </div>
|
||||
<div class="line"><a name="l00075"></a><span class="lineno"> 75</span>  <span class="comment">//nice, pretty parameters we'll give back to the user if they ask what the tunings are</span></div>
|
||||
<div class="line"><a name="l00076"></a><span class="lineno"> 76</span>  <span class="keywordtype">float</span> P_Param;</div>
|
||||
<div class="line"><a name="l00077"></a><span class="lineno"> 77</span>  <span class="keywordtype">float</span> I_Param;</div>
|
||||
<div class="line"><a name="l00078"></a><span class="lineno"> 78</span>  <span class="keywordtype">float</span> D_Param;</div>
|
||||
<div class="line"><a name="l00079"></a><span class="lineno"> 79</span>  </div>
|
||||
<div class="line"><a name="l00080"></a><span class="lineno"> 80</span>  </div>
|
||||
<div class="line"><a name="l00081"></a><span class="lineno"> 81</span>  <span class="keywordtype">int</span> *myInput; <span class="comment">// * Pointers to the Input, Output, and Setpoint variables</span></div>
|
||||
<div class="line"><a name="l00082"></a><span class="lineno"> 82</span>  <span class="keywordtype">int</span> *myOutput; <span class="comment">// This creates a hard link between the variables and the </span></div>
|
||||
<div class="line"><a name="l00083"></a><span class="lineno"> 83</span>  <span class="keywordtype">int</span> *mySetpoint; <span class="comment">// PID, freeing the user from having to constantly tell us</span></div>
|
||||
<div class="line"><a name="l00084"></a><span class="lineno"> 84</span>  <span class="comment">// what these values are. with pointers we'll just know.</span></div>
|
||||
<div class="line"><a name="l00085"></a><span class="lineno"> 85</span>  </div>
|
||||
<div class="line"><a name="l00086"></a><span class="lineno"> 86</span>  <span class="keywordtype">int</span> *myBias; <span class="comment">// * Pointer to the External FeedForward bias, only used </span></div>
|
||||
<div class="line"><a name="l00087"></a><span class="lineno"> 87</span>  <span class="comment">// if the advanced constructor is used</span></div>
|
||||
<div class="line"><a name="l00088"></a><span class="lineno"> 88</span>  <span class="keywordtype">bool</span> UsingFeedForward; <span class="comment">// * internal flag that tells us if we're using FeedForward or not</span></div>
|
||||
<div class="line"><a name="l00089"></a><span class="lineno"> 89</span>  </div>
|
||||
<div class="line"><a name="l00090"></a><span class="lineno"> 90</span>  <span class="keywordtype">unsigned</span> <span class="keywordtype">long</span> nextCompTime; <span class="comment">// * Helps us figure out when the PID Calculation needs to</span></div>
|
||||
<div class="line"><a name="l00091"></a><span class="lineno"> 91</span>  <span class="comment">// be performed next</span></div>
|
||||
<div class="line"><a name="l00092"></a><span class="lineno"> 92</span>  <span class="comment">// to determine when to compute next</span></div>
|
||||
<div class="line"><a name="l00093"></a><span class="lineno"> 93</span>  <span class="keywordtype">unsigned</span> <span class="keywordtype">long</span> tSample; <span class="comment">// * the frequency, in milliseconds, with which we want the</span></div>
|
||||
<div class="line"><a name="l00094"></a><span class="lineno"> 94</span>  <span class="comment">// the PID calculation to occur.</span></div>
|
||||
<div class="line"><a name="l00095"></a><span class="lineno"> 95</span>  <span class="keywordtype">bool</span> inAuto; <span class="comment">// * Flag letting us know if we are in Automatic or not</span></div>
|
||||
<div class="line"><a name="l00096"></a><span class="lineno"> 96</span>  </div>
|
||||
<div class="line"><a name="l00097"></a><span class="lineno"> 97</span>  <span class="comment">// the derivative required for the D term</span></div>
|
||||
<div class="line"><a name="l00098"></a><span class="lineno"> 98</span>  <span class="comment">//float accError; // * the (I)ntegral term is based on the sum of error over</span></div>
|
||||
<div class="line"><a name="l00099"></a><span class="lineno"> 99</span>  <span class="comment">// time. this variable keeps track of that</span></div>
|
||||
<div class="line"><a name="l00100"></a><span class="lineno"> 100</span>  <span class="keywordtype">float</span> bias; <span class="comment">// * the base output from which the PID operates</span></div>
|
||||
<div class="line"><a name="l00101"></a><span class="lineno"> 101</span>  </div>
|
||||
<div class="line"><a name="l00102"></a><span class="lineno"> 102</span>  <span class="keywordtype">int</span> Err;</div>
|
||||
<div class="line"><a name="l00103"></a><span class="lineno"> 103</span>  <span class="keywordtype">int</span> lastErr;</div>
|
||||
<div class="line"><a name="l00104"></a><span class="lineno"> 104</span>  <span class="keywordtype">int</span> prevErr;</div>
|
||||
<div class="line"><a name="l00105"></a><span class="lineno"> 105</span>  </div>
|
||||
<div class="line"><a name="l00106"></a><span class="lineno"> 106</span>  <span class="keywordtype">float</span> inMin, inSpan; <span class="comment">// * input and output limits, and spans. used convert</span></div>
|
||||
<div class="line"><a name="l00107"></a><span class="lineno"> 107</span>  <span class="keywordtype">float</span> outMin, outSpan; <span class="comment">// real world numbers into percent span, with which</span></div>
|
||||
<div class="line"><a name="l00108"></a><span class="lineno"> 108</span>  <span class="comment">// the PID algorithm is more comfortable.</span></div>
|
||||
<div class="line"><a name="l00109"></a><span class="lineno"> 109</span>  </div>
|
||||
<div class="line"><a name="l00110"></a><span class="lineno"> 110</span>  <span class="keywordtype">bool</span> justCalced; <span class="comment">// * flag gets set for one cycle after the pid calculates</span></div>
|
||||
<div class="line"><a name="l00111"></a><span class="lineno"> 111</span> };</div>
|
||||
<div class="line"><a name="l00112"></a><span class="lineno"> 112</span> <span class="preprocessor">#endif</span></div>
|
||||
<div class="line"><a name="l00113"></a><span class="lineno"> 113</span>  </div>
|
||||
<div class="ttc" id="aclassPID_html"><div class="ttname"><a href="classPID.html">PID</a></div><div class="ttdef"><b>Definition:</b> PID_Beta6.h:5</div></div>
|
||||
<div class="ttc" id="aclassPID_html_a05a3258d4b553e7a121f7360ffe88065"><div class="ttname"><a href="classPID.html#a05a3258d4b553e7a121f7360ffe88065">PID::Compute</a></div><div class="ttdeci">void Compute()</div><div class="ttdef"><b>Definition:</b> PID_Beta6.cpp:207</div></div>
|
||||
<div class="ttc" id="aclassPID_html_a34178c5110d89a8029e403f6ef5d003d"><div class="ttname"><a href="classPID.html#a34178c5110d89a8029e403f6ef5d003d">PID::JustCalculated</a></div><div class="ttdeci">bool JustCalculated()</div><div class="ttdef"><b>Definition:</b> PID_Beta6.cpp:266</div></div>
|
||||
<div class="ttc" id="aclassPID_html_a3d18162a81fab3b59b66f2398c2f55da"><div class="ttname"><a href="classPID.html#a3d18162a81fab3b59b66f2398c2f55da">PID::GetOUTMin</a></div><div class="ttdeci">int GetOUTMin()</div><div class="ttdef"><b>Definition:</b> PID_Beta6.cpp:284</div></div>
|
||||
<div class="ttc" id="aclassPID_html_a44a5a23e5ab0ebc59ac56cd6e63a74e9"><div class="ttname"><a href="classPID.html#a44a5a23e5ab0ebc59ac56cd6e63a74e9">PID::GetP_Param</a></div><div class="ttdeci">float GetP_Param()</div><div class="ttdef"><b>Definition:</b> PID_Beta6.cpp:296</div></div>
|
||||
<div class="ttc" id="aclassPID_html_a5dcf844aec5142d13f0e1a9af2eac237"><div class="ttname"><a href="classPID.html#a5dcf844aec5142d13f0e1a9af2eac237">PID::GetI_Param</a></div><div class="ttdeci">float GetI_Param()</div><div class="ttdef"><b>Definition:</b> PID_Beta6.cpp:300</div></div>
|
||||
<div class="ttc" id="aclassPID_html_a68074bad88a8cc442ee03a036073d5d5"><div class="ttname"><a href="classPID.html#a68074bad88a8cc442ee03a036073d5d5">PID::SetMode</a></div><div class="ttdeci">void SetMode(int Mode)</div><div class="ttdef"><b>Definition:</b> PID_Beta6.cpp:156</div></div>
|
||||
<div class="ttc" id="aclassPID_html_a70a457a8b2d0f2306923c30282567af6"><div class="ttname"><a href="classPID.html#a70a457a8b2d0f2306923c30282567af6">PID::PID</a></div><div class="ttdeci">PID(int *, int *, int *, float, float, float)</div><div class="ttdef"><b>Definition:</b> PID_Beta6.cpp:18</div></div>
|
||||
<div class="ttc" id="aclassPID_html_a752d07a63dd8d90191a28d24ea85861c"><div class="ttname"><a href="classPID.html#a752d07a63dd8d90191a28d24ea85861c">PID::GetD_Param</a></div><div class="ttdeci">float GetD_Param()</div><div class="ttdef"><b>Definition:</b> PID_Beta6.cpp:305</div></div>
|
||||
<div class="ttc" id="aclassPID_html_a7a1fbe9bbf606557cef3fcf07f04d3f6"><div class="ttname"><a href="classPID.html#a7a1fbe9bbf606557cef3fcf07f04d3f6">PID::SetOutputLimits</a></div><div class="ttdeci">void SetOutputLimits(int, int)</div><div class="ttdef"><b>Definition:</b> PID_Beta6.cpp:91</div></div>
|
||||
<div class="ttc" id="aclassPID_html_a7c6fb1d00b7ceb89f833c85a10425a99"><div class="ttname"><a href="classPID.html#a7c6fb1d00b7ceb89f833c85a10425a99">PID::GetINMin</a></div><div class="ttdeci">int GetINMin()</div><div class="ttdef"><b>Definition:</b> PID_Beta6.cpp:276</div></div>
|
||||
<div class="ttc" id="aclassPID_html_a9f949fd4445477ee9bf1af2bfa3e1a84"><div class="ttname"><a href="classPID.html#a9f949fd4445477ee9bf1af2bfa3e1a84">PID::Reset</a></div><div class="ttdeci">void Reset()</div><div class="ttdef"><b>Definition:</b> PID_Beta6.cpp:141</div></div>
|
||||
<div class="ttc" id="aclassPID_html_aa51d6ef0803413fd0da475406a5ae6ad"><div class="ttname"><a href="classPID.html#aa51d6ef0803413fd0da475406a5ae6ad">PID::SetTunings</a></div><div class="ttdeci">void SetTunings(float, float, float)</div><div class="ttdef"><b>Definition:</b> PID_Beta6.cpp:105</div></div>
|
||||
<div class="ttc" id="aclassPID_html_aa84bd27695ea7b6f80a0a6170abb410f"><div class="ttname"><a href="classPID.html#aa84bd27695ea7b6f80a0a6170abb410f">PID::SetInputLimits</a></div><div class="ttdeci">void SetInputLimits(int, int)</div><div class="ttdef"><b>Definition:</b> PID_Beta6.cpp:73</div></div>
|
||||
<div class="ttc" id="aclassPID_html_aaa1e0e67a0c97571bd62b326e6cf3b2e"><div class="ttname"><a href="classPID.html#aaa1e0e67a0c97571bd62b326e6cf3b2e">PID::SetSampleTime</a></div><div class="ttdeci">void SetSampleTime(int)</div><div class="ttdef"><b>Definition:</b> PID_Beta6.cpp:169</div></div>
|
||||
<div class="ttc" id="aclassPID_html_aada1bd2d75fc4cfb8d4e8b3bb7d6efb3"><div class="ttname"><a href="classPID.html#aada1bd2d75fc4cfb8d4e8b3bb7d6efb3">PID::GetINMax</a></div><div class="ttdeci">int GetINMax()</div><div class="ttdef"><b>Definition:</b> PID_Beta6.cpp:280</div></div>
|
||||
<div class="ttc" id="aclassPID_html_acc325db5e6a140b92c8199a66e03491b"><div class="ttname"><a href="classPID.html#acc325db5e6a140b92c8199a66e03491b">PID::GetMode</a></div><div class="ttdeci">int GetMode()</div><div class="ttdef"><b>Definition:</b> PID_Beta6.cpp:270</div></div>
|
||||
<div class="ttc" id="aclassPID_html_aefa4318e7ab26fbdfd7a2f6870d694e8"><div class="ttname"><a href="classPID.html#aefa4318e7ab26fbdfd7a2f6870d694e8">PID::GetSampleTime</a></div><div class="ttdeci">int GetSampleTime()</div><div class="ttdef"><b>Definition:</b> PID_Beta6.cpp:292</div></div>
|
||||
<div class="ttc" id="aclassPID_html_afca76f72062cde15b4d738b693215bf6"><div class="ttname"><a href="classPID.html#afca76f72062cde15b4d738b693215bf6">PID::GetOUTMax</a></div><div class="ttdeci">int GetOUTMax()</div><div class="ttdef"><b>Definition:</b> PID_Beta6.cpp:288</div></div>
|
||||
</div><!-- fragment --></div><!-- contents -->
|
||||
<!-- start footer part -->
|
||||
<hr class="footer"/><address class="footer"><small>
|
||||
Generated by <a href="https://www.doxygen.org/index.html"><img class="footer" src="doxygen.svg" width="104" height="31" alt="doxygen"/></a> 1.9.1
|
||||
</small></address>
|
||||
</body>
|
||||
</html>
|
@ -1,96 +0,0 @@
|
||||
<!DOCTYPE html PUBLIC "-//W3C//DTD XHTML 1.0 Transitional//EN" "https://www.w3.org/TR/xhtml1/DTD/xhtml1-transitional.dtd">
|
||||
<html xmlns="http://www.w3.org/1999/xhtml">
|
||||
<head>
|
||||
<meta http-equiv="Content-Type" content="text/xhtml;charset=UTF-8"/>
|
||||
<meta http-equiv="X-UA-Compatible" content="IE=9"/>
|
||||
<meta name="generator" content="Doxygen 1.9.1"/>
|
||||
<meta name="viewport" content="width=device-width, initial-scale=1"/>
|
||||
<title>DCAITI Robot Hardware: lib/PinChangeInt/PinChangeIntConfig.h File Reference</title>
|
||||
<link href="tabs.css" rel="stylesheet" type="text/css"/>
|
||||
<script type="text/javascript" src="jquery.js"></script>
|
||||
<script type="text/javascript" src="dynsections.js"></script>
|
||||
<link href="search/search.css" rel="stylesheet" type="text/css"/>
|
||||
<script type="text/javascript" src="search/searchdata.js"></script>
|
||||
<script type="text/javascript" src="search/search.js"></script>
|
||||
<link href="doxygen.css" rel="stylesheet" type="text/css" />
|
||||
</head>
|
||||
<body>
|
||||
<div id="top"><!-- do not remove this div, it is closed by doxygen! -->
|
||||
<div id="titlearea">
|
||||
<table cellspacing="0" cellpadding="0">
|
||||
<tbody>
|
||||
<tr style="height: 56px;">
|
||||
<td id="projectalign" style="padding-left: 0.5em;">
|
||||
<div id="projectname">DCAITI Robot Hardware
|
||||
 <span id="projectnumber">1.0</span>
|
||||
</div>
|
||||
</td>
|
||||
</tr>
|
||||
</tbody>
|
||||
</table>
|
||||
</div>
|
||||
<!-- end header part -->
|
||||
<!-- Generated by Doxygen 1.9.1 -->
|
||||
<script type="text/javascript">
|
||||
/* @license magnet:?xt=urn:btih:cf05388f2679ee054f2beb29a391d25f4e673ac3&dn=gpl-2.0.txt GPL-v2 */
|
||||
var searchBox = new SearchBox("searchBox", "search",false,'Search','.html');
|
||||
/* @license-end */
|
||||
</script>
|
||||
<script type="text/javascript" src="menudata.js"></script>
|
||||
<script type="text/javascript" src="menu.js"></script>
|
||||
<script type="text/javascript">
|
||||
/* @license magnet:?xt=urn:btih:cf05388f2679ee054f2beb29a391d25f4e673ac3&dn=gpl-2.0.txt GPL-v2 */
|
||||
$(function() {
|
||||
initMenu('',true,false,'search.php','Search');
|
||||
$(document).ready(function() { init_search(); });
|
||||
});
|
||||
/* @license-end */</script>
|
||||
<div id="main-nav"></div>
|
||||
<!-- window showing the filter options -->
|
||||
<div id="MSearchSelectWindow"
|
||||
onmouseover="return searchBox.OnSearchSelectShow()"
|
||||
onmouseout="return searchBox.OnSearchSelectHide()"
|
||||
onkeydown="return searchBox.OnSearchSelectKey(event)">
|
||||
</div>
|
||||
|
||||
<!-- iframe showing the search results (closed by default) -->
|
||||
<div id="MSearchResultsWindow">
|
||||
<iframe src="javascript:void(0)" frameborder="0"
|
||||
name="MSearchResults" id="MSearchResults">
|
||||
</iframe>
|
||||
</div>
|
||||
|
||||
<div id="nav-path" class="navpath">
|
||||
<ul>
|
||||
<li class="navelem"><a class="el" href="dir_97aefd0d527b934f1d99a682da8fe6a9.html">lib</a></li><li class="navelem"><a class="el" href="dir_0f386e5012f166522d8afb320f99104b.html">PinChangeInt</a></li> </ul>
|
||||
</div>
|
||||
</div><!-- top -->
|
||||
<div class="header">
|
||||
<div class="headertitle">
|
||||
<div class="title">PinChangeIntConfig.h File Reference</div> </div>
|
||||
</div><!--header-->
|
||||
<div class="contents">
|
||||
<div class="textblock"><div class="dynheader">
|
||||
This graph shows which files directly or indirectly include this file:</div>
|
||||
<div class="dyncontent">
|
||||
<div class="center"><img src="PinChangeIntConfig_8h__dep__incl.png" border="0" usemap="#alib_2PinChangeInt_2PinChangeIntConfig_8hdep" alt=""/></div>
|
||||
<map name="alib_2PinChangeInt_2PinChangeIntConfig_8hdep" id="alib_2PinChangeInt_2PinChangeIntConfig_8hdep">
|
||||
<area shape="rect" title=" " alt="" coords="28,5,229,47"/>
|
||||
<area shape="rect" href="main_8cpp.html" title=" " alt="" coords="5,273,111,300"/>
|
||||
<area shape="rect" href="PinChangeInt_8h.html" title=" " alt="" coords="125,95,327,136"/>
|
||||
<area shape="rect" href="MotorWheel_8h.html" title=" " alt="" coords="147,191,363,218"/>
|
||||
<area shape="rect" href="PinChangeInt_8cpp.html" title=" " alt="" coords="388,184,589,225"/>
|
||||
<area shape="rect" href="UARTCom_8cpp.html" title=" " alt="" coords="135,273,378,300"/>
|
||||
<area shape="rect" href="UCommands_8cpp.html" title=" " alt="" coords="402,273,663,300"/>
|
||||
<area shape="rect" href="MotorWheel_8cpp.html" title=" " alt="" coords="688,273,919,300"/>
|
||||
</map>
|
||||
</div>
|
||||
</div>
|
||||
<p><a href="PinChangeIntConfig_8h_source.html">Go to the source code of this file.</a></p>
|
||||
</div><!-- contents -->
|
||||
<!-- start footer part -->
|
||||
<hr class="footer"/><address class="footer"><small>
|
||||
Generated by <a href="https://www.doxygen.org/index.html"><img class="footer" src="doxygen.svg" width="104" height="31" alt="doxygen"/></a> 1.9.1
|
||||
</small></address>
|
||||
</body>
|
||||
</html>
|
@ -1,10 +0,0 @@
|
||||
<map id="lib/PinChangeInt/PinChangeIntConfig.h" name="lib/PinChangeInt/PinChangeIntConfig.h">
|
||||
<area shape="rect" id="node1" title=" " alt="" coords="28,5,229,47"/>
|
||||
<area shape="rect" id="node2" href="$main_8cpp.html" title=" " alt="" coords="5,273,111,300"/>
|
||||
<area shape="rect" id="node3" href="$PinChangeInt_8h.html" title=" " alt="" coords="125,95,327,136"/>
|
||||
<area shape="rect" id="node4" href="$MotorWheel_8h.html" title=" " alt="" coords="147,191,363,218"/>
|
||||
<area shape="rect" id="node8" href="$PinChangeInt_8cpp.html" title=" " alt="" coords="388,184,589,225"/>
|
||||
<area shape="rect" id="node5" href="$UARTCom_8cpp.html" title=" " alt="" coords="135,273,378,300"/>
|
||||
<area shape="rect" id="node6" href="$UCommands_8cpp.html" title=" " alt="" coords="402,273,663,300"/>
|
||||
<area shape="rect" id="node7" href="$MotorWheel_8cpp.html" title=" " alt="" coords="688,273,919,300"/>
|
||||
</map>
|
@ -1 +0,0 @@
|
||||
5f0a727aa5bc469422fee273d2254040
|
Before Width: | Height: | Size: 26 KiB |
@ -1,99 +0,0 @@
|
||||
<!DOCTYPE html PUBLIC "-//W3C//DTD XHTML 1.0 Transitional//EN" "https://www.w3.org/TR/xhtml1/DTD/xhtml1-transitional.dtd">
|
||||
<html xmlns="http://www.w3.org/1999/xhtml">
|
||||
<head>
|
||||
<meta http-equiv="Content-Type" content="text/xhtml;charset=UTF-8"/>
|
||||
<meta http-equiv="X-UA-Compatible" content="IE=9"/>
|
||||
<meta name="generator" content="Doxygen 1.9.1"/>
|
||||
<meta name="viewport" content="width=device-width, initial-scale=1"/>
|
||||
<title>DCAITI Robot Hardware: lib/PinChangeInt/PinChangeIntConfig.h Source File</title>
|
||||
<link href="tabs.css" rel="stylesheet" type="text/css"/>
|
||||
<script type="text/javascript" src="jquery.js"></script>
|
||||
<script type="text/javascript" src="dynsections.js"></script>
|
||||
<link href="search/search.css" rel="stylesheet" type="text/css"/>
|
||||
<script type="text/javascript" src="search/searchdata.js"></script>
|
||||
<script type="text/javascript" src="search/search.js"></script>
|
||||
<link href="doxygen.css" rel="stylesheet" type="text/css" />
|
||||
</head>
|
||||
<body>
|
||||
<div id="top"><!-- do not remove this div, it is closed by doxygen! -->
|
||||
<div id="titlearea">
|
||||
<table cellspacing="0" cellpadding="0">
|
||||
<tbody>
|
||||
<tr style="height: 56px;">
|
||||
<td id="projectalign" style="padding-left: 0.5em;">
|
||||
<div id="projectname">DCAITI Robot Hardware
|
||||
 <span id="projectnumber">1.0</span>
|
||||
</div>
|
||||
</td>
|
||||
</tr>
|
||||
</tbody>
|
||||
</table>
|
||||
</div>
|
||||
<!-- end header part -->
|
||||
<!-- Generated by Doxygen 1.9.1 -->
|
||||
<script type="text/javascript">
|
||||
/* @license magnet:?xt=urn:btih:cf05388f2679ee054f2beb29a391d25f4e673ac3&dn=gpl-2.0.txt GPL-v2 */
|
||||
var searchBox = new SearchBox("searchBox", "search",false,'Search','.html');
|
||||
/* @license-end */
|
||||
</script>
|
||||
<script type="text/javascript" src="menudata.js"></script>
|
||||
<script type="text/javascript" src="menu.js"></script>
|
||||
<script type="text/javascript">
|
||||
/* @license magnet:?xt=urn:btih:cf05388f2679ee054f2beb29a391d25f4e673ac3&dn=gpl-2.0.txt GPL-v2 */
|
||||
$(function() {
|
||||
initMenu('',true,false,'search.php','Search');
|
||||
$(document).ready(function() { init_search(); });
|
||||
});
|
||||
/* @license-end */</script>
|
||||
<div id="main-nav"></div>
|
||||
<!-- window showing the filter options -->
|
||||
<div id="MSearchSelectWindow"
|
||||
onmouseover="return searchBox.OnSearchSelectShow()"
|
||||
onmouseout="return searchBox.OnSearchSelectHide()"
|
||||
onkeydown="return searchBox.OnSearchSelectKey(event)">
|
||||
</div>
|
||||
|
||||
<!-- iframe showing the search results (closed by default) -->
|
||||
<div id="MSearchResultsWindow">
|
||||
<iframe src="javascript:void(0)" frameborder="0"
|
||||
name="MSearchResults" id="MSearchResults">
|
||||
</iframe>
|
||||
</div>
|
||||
|
||||
<div id="nav-path" class="navpath">
|
||||
<ul>
|
||||
<li class="navelem"><a class="el" href="dir_97aefd0d527b934f1d99a682da8fe6a9.html">lib</a></li><li class="navelem"><a class="el" href="dir_0f386e5012f166522d8afb320f99104b.html">PinChangeInt</a></li> </ul>
|
||||
</div>
|
||||
</div><!-- top -->
|
||||
<div class="header">
|
||||
<div class="headertitle">
|
||||
<div class="title">PinChangeIntConfig.h</div> </div>
|
||||
</div><!--header-->
|
||||
<div class="contents">
|
||||
<a href="PinChangeIntConfig_8h.html">Go to the documentation of this file.</a><div class="fragment"><div class="line"><a name="l00001"></a><span class="lineno"> 1</span>  </div>
|
||||
<div class="line"><a name="l00002"></a><span class="lineno"> 2</span> <span class="comment">// This file is used to separate the changes you make to personalize the </span></div>
|
||||
<div class="line"><a name="l00003"></a><span class="lineno"> 3</span> <span class="comment">// Pin Change Interrupt library from any future changes to the library itself.</span></div>
|
||||
<div class="line"><a name="l00004"></a><span class="lineno"> 4</span> <span class="comment">// Ideally it would reside in the folder of the current sketch, but I have not </span></div>
|
||||
<div class="line"><a name="l00005"></a><span class="lineno"> 5</span> <span class="comment">// figured out how such a file can be included from a library.</span></div>
|
||||
<div class="line"><a name="l00006"></a><span class="lineno"> 6</span> <span class="comment">// Nothing is required to be defined within this file since default values are</span></div>
|
||||
<div class="line"><a name="l00007"></a><span class="lineno"> 7</span> <span class="comment">// defined in the primary PinChangeInt.h file.</span></div>
|
||||
<div class="line"><a name="l00008"></a><span class="lineno"> 8</span>  </div>
|
||||
<div class="line"><a name="l00009"></a><span class="lineno"> 9</span> <span class="comment">// Uncomment the line below to limit the handler to servicing a single interrupt per invocation.</span></div>
|
||||
<div class="line"><a name="l00010"></a><span class="lineno"> 10</span> <span class="comment">//#define DISABLE_PCINT_MULTI_SERVICE</span></div>
|
||||
<div class="line"><a name="l00011"></a><span class="lineno"> 11</span>  </div>
|
||||
<div class="line"><a name="l00012"></a><span class="lineno"> 12</span> <span class="comment">// Define the value MAX_PIN_CHANGE_PINS to limit the number of pins that may be </span></div>
|
||||
<div class="line"><a name="l00013"></a><span class="lineno"> 13</span> <span class="comment">// used for pin change interrupts. This value determines the number of pin change </span></div>
|
||||
<div class="line"><a name="l00014"></a><span class="lineno"> 14</span> <span class="comment">// interrupts supported for all ports.</span></div>
|
||||
<div class="line"><a name="l00015"></a><span class="lineno"> 15</span> <span class="comment">//#define MAX_PIN_CHANGE_PINS 2</span></div>
|
||||
<div class="line"><a name="l00016"></a><span class="lineno"> 16</span>  </div>
|
||||
<div class="line"><a name="l00017"></a><span class="lineno"> 17</span> <span class="comment">// declare ports without pin change interrupts used</span></div>
|
||||
<div class="line"><a name="l00018"></a><span class="lineno"> 18</span> <span class="comment">//#define NO_PORTB_PINCHANGES</span></div>
|
||||
<div class="line"><a name="l00019"></a><span class="lineno"> 19</span> <span class="comment">//#define NO_PORTC_PINCHANGES</span></div>
|
||||
<div class="line"><a name="l00020"></a><span class="lineno"> 20</span> <span class="comment">//#define NO_PORTD_PINCHANGES</span></div>
|
||||
</div><!-- fragment --></div><!-- contents -->
|
||||
<!-- start footer part -->
|
||||
<hr class="footer"/><address class="footer"><small>
|
||||
Generated by <a href="https://www.doxygen.org/index.html"><img class="footer" src="doxygen.svg" width="104" height="31" alt="doxygen"/></a> 1.9.1
|
||||
</small></address>
|
||||
</body>
|
||||
</html>
|
@ -1,186 +0,0 @@
|
||||
<!DOCTYPE html PUBLIC "-//W3C//DTD XHTML 1.0 Transitional//EN" "https://www.w3.org/TR/xhtml1/DTD/xhtml1-transitional.dtd">
|
||||
<html xmlns="http://www.w3.org/1999/xhtml">
|
||||
<head>
|
||||
<meta http-equiv="Content-Type" content="text/xhtml;charset=UTF-8"/>
|
||||
<meta http-equiv="X-UA-Compatible" content="IE=9"/>
|
||||
<meta name="generator" content="Doxygen 1.9.1"/>
|
||||
<meta name="viewport" content="width=device-width, initial-scale=1"/>
|
||||
<title>DCAITI Robot Hardware: lib/PinChangeInt/PinChangeInt.cpp File Reference</title>
|
||||
<link href="tabs.css" rel="stylesheet" type="text/css"/>
|
||||
<script type="text/javascript" src="jquery.js"></script>
|
||||
<script type="text/javascript" src="dynsections.js"></script>
|
||||
<link href="search/search.css" rel="stylesheet" type="text/css"/>
|
||||
<script type="text/javascript" src="search/searchdata.js"></script>
|
||||
<script type="text/javascript" src="search/search.js"></script>
|
||||
<link href="doxygen.css" rel="stylesheet" type="text/css" />
|
||||
</head>
|
||||
<body>
|
||||
<div id="top"><!-- do not remove this div, it is closed by doxygen! -->
|
||||
<div id="titlearea">
|
||||
<table cellspacing="0" cellpadding="0">
|
||||
<tbody>
|
||||
<tr style="height: 56px;">
|
||||
<td id="projectalign" style="padding-left: 0.5em;">
|
||||
<div id="projectname">DCAITI Robot Hardware
|
||||
 <span id="projectnumber">1.0</span>
|
||||
</div>
|
||||
</td>
|
||||
</tr>
|
||||
</tbody>
|
||||
</table>
|
||||
</div>
|
||||
<!-- end header part -->
|
||||
<!-- Generated by Doxygen 1.9.1 -->
|
||||
<script type="text/javascript">
|
||||
/* @license magnet:?xt=urn:btih:cf05388f2679ee054f2beb29a391d25f4e673ac3&dn=gpl-2.0.txt GPL-v2 */
|
||||
var searchBox = new SearchBox("searchBox", "search",false,'Search','.html');
|
||||
/* @license-end */
|
||||
</script>
|
||||
<script type="text/javascript" src="menudata.js"></script>
|
||||
<script type="text/javascript" src="menu.js"></script>
|
||||
<script type="text/javascript">
|
||||
/* @license magnet:?xt=urn:btih:cf05388f2679ee054f2beb29a391d25f4e673ac3&dn=gpl-2.0.txt GPL-v2 */
|
||||
$(function() {
|
||||
initMenu('',true,false,'search.php','Search');
|
||||
$(document).ready(function() { init_search(); });
|
||||
});
|
||||
/* @license-end */</script>
|
||||
<div id="main-nav"></div>
|
||||
<!-- window showing the filter options -->
|
||||
<div id="MSearchSelectWindow"
|
||||
onmouseover="return searchBox.OnSearchSelectShow()"
|
||||
onmouseout="return searchBox.OnSearchSelectHide()"
|
||||
onkeydown="return searchBox.OnSearchSelectKey(event)">
|
||||
</div>
|
||||
|
||||
<!-- iframe showing the search results (closed by default) -->
|
||||
<div id="MSearchResultsWindow">
|
||||
<iframe src="javascript:void(0)" frameborder="0"
|
||||
name="MSearchResults" id="MSearchResults">
|
||||
</iframe>
|
||||
</div>
|
||||
|
||||
<div id="nav-path" class="navpath">
|
||||
<ul>
|
||||
<li class="navelem"><a class="el" href="dir_97aefd0d527b934f1d99a682da8fe6a9.html">lib</a></li><li class="navelem"><a class="el" href="dir_0f386e5012f166522d8afb320f99104b.html">PinChangeInt</a></li> </ul>
|
||||
</div>
|
||||
</div><!-- top -->
|
||||
<div class="header">
|
||||
<div class="summary">
|
||||
<a href="#func-members">Functions</a> </div>
|
||||
<div class="headertitle">
|
||||
<div class="title">PinChangeInt.cpp File Reference</div> </div>
|
||||
</div><!--header-->
|
||||
<div class="contents">
|
||||
<div class="textblock"><code>#include <<a class="el" href="PinChangeInt_8h_source.html">PinChangeInt.h</a>></code><br />
|
||||
</div><div class="textblock"><div class="dynheader">
|
||||
Include dependency graph for PinChangeInt.cpp:</div>
|
||||
<div class="dyncontent">
|
||||
<div class="center"><img src="PinChangeInt_8cpp__incl.png" border="0" usemap="#alib_2PinChangeInt_2PinChangeInt_8cpp" alt=""/></div>
|
||||
<map name="alib_2PinChangeInt_2PinChangeInt_8cpp" id="alib_2PinChangeInt_2PinChangeInt_8cpp">
|
||||
<area shape="rect" title=" " alt="" coords="113,5,315,47"/>
|
||||
<area shape="rect" href="PinChangeInt_8h.html" title=" " alt="" coords="154,95,274,121"/>
|
||||
<area shape="rect" title=" " alt="" coords="5,169,108,196"/>
|
||||
<area shape="rect" href="PinChangeIntConfig_8h.html" title=" " alt="" coords="133,169,295,196"/>
|
||||
<area shape="rect" title=" " alt="" coords="319,169,437,196"/>
|
||||
</map>
|
||||
</div>
|
||||
</div><table class="memberdecls">
|
||||
<tr class="heading"><td colspan="2"><h2 class="groupheader"><a name="func-members"></a>
|
||||
Functions</h2></td></tr>
|
||||
<tr class="memitem:aa64c6dce15e9de9105b4ae9533c9a267"><td class="memItemLeft" align="right" valign="top"> </td><td class="memItemRight" valign="bottom"><a class="el" href="PinChangeInt_8cpp.html#aa64c6dce15e9de9105b4ae9533c9a267">ISR</a> (PCINT0_vect)</td></tr>
|
||||
<tr class="separator:aa64c6dce15e9de9105b4ae9533c9a267"><td class="memSeparator" colspan="2"> </td></tr>
|
||||
<tr class="memitem:afe6035149a64d5f448fbda08e9d1b67f"><td class="memItemLeft" align="right" valign="top"> </td><td class="memItemRight" valign="bottom"><a class="el" href="PinChangeInt_8cpp.html#afe6035149a64d5f448fbda08e9d1b67f">ISR</a> (PCINT1_vect)</td></tr>
|
||||
<tr class="separator:afe6035149a64d5f448fbda08e9d1b67f"><td class="memSeparator" colspan="2"> </td></tr>
|
||||
<tr class="memitem:a9c4665742c6b6eb1f0bb9dde41f7cba3"><td class="memItemLeft" align="right" valign="top"> </td><td class="memItemRight" valign="bottom"><a class="el" href="PinChangeInt_8cpp.html#a9c4665742c6b6eb1f0bb9dde41f7cba3">ISR</a> (PCINT2_vect)</td></tr>
|
||||
<tr class="separator:a9c4665742c6b6eb1f0bb9dde41f7cba3"><td class="memSeparator" colspan="2"> </td></tr>
|
||||
</table>
|
||||
<h2 class="groupheader">Function Documentation</h2>
|
||||
<a id="aa64c6dce15e9de9105b4ae9533c9a267"></a>
|
||||
<h2 class="memtitle"><span class="permalink"><a href="#aa64c6dce15e9de9105b4ae9533c9a267">◆ </a></span>ISR() <span class="overload">[1/3]</span></h2>
|
||||
|
||||
<div class="memitem">
|
||||
<div class="memproto">
|
||||
<table class="memname">
|
||||
<tr>
|
||||
<td class="memname">ISR </td>
|
||||
<td>(</td>
|
||||
<td class="paramtype">PCINT0_vect </td>
|
||||
<td class="paramname"></td><td>)</td>
|
||||
<td></td>
|
||||
</tr>
|
||||
</table>
|
||||
</div><div class="memdoc">
|
||||
<div class="dynheader">
|
||||
Here is the call graph for this function:</div>
|
||||
<div class="dyncontent">
|
||||
<div class="center"><img src="PinChangeInt_8cpp_aa64c6dce15e9de9105b4ae9533c9a267_cgraph.png" border="0" usemap="#aPinChangeInt_8cpp_aa64c6dce15e9de9105b4ae9533c9a267_cgraph" alt=""/></div>
|
||||
<map name="aPinChangeInt_8cpp_aa64c6dce15e9de9105b4ae9533c9a267_cgraph" id="aPinChangeInt_8cpp_aa64c6dce15e9de9105b4ae9533c9a267_cgraph">
|
||||
<area shape="rect" title=" " alt="" coords="5,5,48,32"/>
|
||||
<area shape="rect" href="classPCintPort.html#a576bbb5d4190a7af0de2528760933916" title=" " alt="" coords="96,5,220,32"/>
|
||||
</map>
|
||||
</div>
|
||||
|
||||
</div>
|
||||
</div>
|
||||
<a id="afe6035149a64d5f448fbda08e9d1b67f"></a>
|
||||
<h2 class="memtitle"><span class="permalink"><a href="#afe6035149a64d5f448fbda08e9d1b67f">◆ </a></span>ISR() <span class="overload">[2/3]</span></h2>
|
||||
|
||||
<div class="memitem">
|
||||
<div class="memproto">
|
||||
<table class="memname">
|
||||
<tr>
|
||||
<td class="memname">ISR </td>
|
||||
<td>(</td>
|
||||
<td class="paramtype">PCINT1_vect </td>
|
||||
<td class="paramname"></td><td>)</td>
|
||||
<td></td>
|
||||
</tr>
|
||||
</table>
|
||||
</div><div class="memdoc">
|
||||
<div class="dynheader">
|
||||
Here is the call graph for this function:</div>
|
||||
<div class="dyncontent">
|
||||
<div class="center"><img src="PinChangeInt_8cpp_afe6035149a64d5f448fbda08e9d1b67f_cgraph.png" border="0" usemap="#aPinChangeInt_8cpp_afe6035149a64d5f448fbda08e9d1b67f_cgraph" alt=""/></div>
|
||||
<map name="aPinChangeInt_8cpp_afe6035149a64d5f448fbda08e9d1b67f_cgraph" id="aPinChangeInt_8cpp_afe6035149a64d5f448fbda08e9d1b67f_cgraph">
|
||||
<area shape="rect" title=" " alt="" coords="5,5,48,32"/>
|
||||
<area shape="rect" href="classPCintPort.html#a576bbb5d4190a7af0de2528760933916" title=" " alt="" coords="96,5,220,32"/>
|
||||
</map>
|
||||
</div>
|
||||
|
||||
</div>
|
||||
</div>
|
||||
<a id="a9c4665742c6b6eb1f0bb9dde41f7cba3"></a>
|
||||
<h2 class="memtitle"><span class="permalink"><a href="#a9c4665742c6b6eb1f0bb9dde41f7cba3">◆ </a></span>ISR() <span class="overload">[3/3]</span></h2>
|
||||
|
||||
<div class="memitem">
|
||||
<div class="memproto">
|
||||
<table class="memname">
|
||||
<tr>
|
||||
<td class="memname">ISR </td>
|
||||
<td>(</td>
|
||||
<td class="paramtype">PCINT2_vect </td>
|
||||
<td class="paramname"></td><td>)</td>
|
||||
<td></td>
|
||||
</tr>
|
||||
</table>
|
||||
</div><div class="memdoc">
|
||||
<div class="dynheader">
|
||||
Here is the call graph for this function:</div>
|
||||
<div class="dyncontent">
|
||||
<div class="center"><img src="PinChangeInt_8cpp_a9c4665742c6b6eb1f0bb9dde41f7cba3_cgraph.png" border="0" usemap="#aPinChangeInt_8cpp_a9c4665742c6b6eb1f0bb9dde41f7cba3_cgraph" alt=""/></div>
|
||||
<map name="aPinChangeInt_8cpp_a9c4665742c6b6eb1f0bb9dde41f7cba3_cgraph" id="aPinChangeInt_8cpp_a9c4665742c6b6eb1f0bb9dde41f7cba3_cgraph">
|
||||
<area shape="rect" title=" " alt="" coords="5,5,48,32"/>
|
||||
<area shape="rect" href="classPCintPort.html#a576bbb5d4190a7af0de2528760933916" title=" " alt="" coords="96,5,220,32"/>
|
||||
</map>
|
||||
</div>
|
||||
|
||||
</div>
|
||||
</div>
|
||||
</div><!-- contents -->
|
||||
<!-- start footer part -->
|
||||
<hr class="footer"/><address class="footer"><small>
|
||||
Generated by <a href="https://www.doxygen.org/index.html"><img class="footer" src="doxygen.svg" width="104" height="31" alt="doxygen"/></a> 1.9.1
|
||||
</small></address>
|
||||
</body>
|
||||
</html>
|
@ -1,7 +0,0 @@
|
||||
<map id="lib/PinChangeInt/PinChangeInt.cpp" name="lib/PinChangeInt/PinChangeInt.cpp">
|
||||
<area shape="rect" id="node1" title=" " alt="" coords="113,5,315,47"/>
|
||||
<area shape="rect" id="node2" href="$PinChangeInt_8h.html" title=" " alt="" coords="154,95,274,121"/>
|
||||
<area shape="rect" id="node3" title=" " alt="" coords="5,169,108,196"/>
|
||||
<area shape="rect" id="node4" href="$PinChangeIntConfig_8h.html" title=" " alt="" coords="133,169,295,196"/>
|
||||
<area shape="rect" id="node5" title=" " alt="" coords="319,169,437,196"/>
|
||||
</map>
|
@ -1 +0,0 @@
|
||||
3c54e574e4eb0c5e060c1f02cb67729c
|
Before Width: | Height: | Size: 9.5 KiB |
@ -1,4 +0,0 @@
|
||||
<map id="ISR" name="ISR">
|
||||
<area shape="rect" id="node1" title=" " alt="" coords="5,5,48,32"/>
|
||||
<area shape="rect" id="node2" href="$classPCintPort.html#a576bbb5d4190a7af0de2528760933916" title=" " alt="" coords="96,5,220,32"/>
|
||||
</map>
|
@ -1 +0,0 @@
|
||||
10223772c650ec8b1b0657423f5b0af2
|
Before Width: | Height: | Size: 1.8 KiB |
@ -1,4 +0,0 @@
|
||||
<map id="ISR" name="ISR">
|
||||
<area shape="rect" id="node1" title=" " alt="" coords="5,5,48,32"/>
|
||||
<area shape="rect" id="node2" href="$classPCintPort.html#a576bbb5d4190a7af0de2528760933916" title=" " alt="" coords="96,5,220,32"/>
|
||||
</map>
|
@ -1 +0,0 @@
|
||||
10223772c650ec8b1b0657423f5b0af2
|
Before Width: | Height: | Size: 1.8 KiB |
@ -1,4 +0,0 @@
|
||||
<map id="ISR" name="ISR">
|
||||
<area shape="rect" id="node1" title=" " alt="" coords="5,5,48,32"/>
|
||||
<area shape="rect" id="node2" href="$classPCintPort.html#a576bbb5d4190a7af0de2528760933916" title=" " alt="" coords="96,5,220,32"/>
|
||||
</map>
|
@ -1 +0,0 @@
|
||||
10223772c650ec8b1b0657423f5b0af2
|
Before Width: | Height: | Size: 1.8 KiB |
@ -1,233 +0,0 @@
|
||||
<!DOCTYPE html PUBLIC "-//W3C//DTD XHTML 1.0 Transitional//EN" "https://www.w3.org/TR/xhtml1/DTD/xhtml1-transitional.dtd">
|
||||
<html xmlns="http://www.w3.org/1999/xhtml">
|
||||
<head>
|
||||
<meta http-equiv="Content-Type" content="text/xhtml;charset=UTF-8"/>
|
||||
<meta http-equiv="X-UA-Compatible" content="IE=9"/>
|
||||
<meta name="generator" content="Doxygen 1.9.1"/>
|
||||
<meta name="viewport" content="width=device-width, initial-scale=1"/>
|
||||
<title>DCAITI Robot Hardware: lib/PinChangeInt/PinChangeInt.h File Reference</title>
|
||||
<link href="tabs.css" rel="stylesheet" type="text/css"/>
|
||||
<script type="text/javascript" src="jquery.js"></script>
|
||||
<script type="text/javascript" src="dynsections.js"></script>
|
||||
<link href="search/search.css" rel="stylesheet" type="text/css"/>
|
||||
<script type="text/javascript" src="search/searchdata.js"></script>
|
||||
<script type="text/javascript" src="search/search.js"></script>
|
||||
<link href="doxygen.css" rel="stylesheet" type="text/css" />
|
||||
</head>
|
||||
<body>
|
||||
<div id="top"><!-- do not remove this div, it is closed by doxygen! -->
|
||||
<div id="titlearea">
|
||||
<table cellspacing="0" cellpadding="0">
|
||||
<tbody>
|
||||
<tr style="height: 56px;">
|
||||
<td id="projectalign" style="padding-left: 0.5em;">
|
||||
<div id="projectname">DCAITI Robot Hardware
|
||||
 <span id="projectnumber">1.0</span>
|
||||
</div>
|
||||
</td>
|
||||
</tr>
|
||||
</tbody>
|
||||
</table>
|
||||
</div>
|
||||
<!-- end header part -->
|
||||
<!-- Generated by Doxygen 1.9.1 -->
|
||||
<script type="text/javascript">
|
||||
/* @license magnet:?xt=urn:btih:cf05388f2679ee054f2beb29a391d25f4e673ac3&dn=gpl-2.0.txt GPL-v2 */
|
||||
var searchBox = new SearchBox("searchBox", "search",false,'Search','.html');
|
||||
/* @license-end */
|
||||
</script>
|
||||
<script type="text/javascript" src="menudata.js"></script>
|
||||
<script type="text/javascript" src="menu.js"></script>
|
||||
<script type="text/javascript">
|
||||
/* @license magnet:?xt=urn:btih:cf05388f2679ee054f2beb29a391d25f4e673ac3&dn=gpl-2.0.txt GPL-v2 */
|
||||
$(function() {
|
||||
initMenu('',true,false,'search.php','Search');
|
||||
$(document).ready(function() { init_search(); });
|
||||
});
|
||||
/* @license-end */</script>
|
||||
<div id="main-nav"></div>
|
||||
<!-- window showing the filter options -->
|
||||
<div id="MSearchSelectWindow"
|
||||
onmouseover="return searchBox.OnSearchSelectShow()"
|
||||
onmouseout="return searchBox.OnSearchSelectHide()"
|
||||
onkeydown="return searchBox.OnSearchSelectKey(event)">
|
||||
</div>
|
||||
|
||||
<!-- iframe showing the search results (closed by default) -->
|
||||
<div id="MSearchResultsWindow">
|
||||
<iframe src="javascript:void(0)" frameborder="0"
|
||||
name="MSearchResults" id="MSearchResults">
|
||||
</iframe>
|
||||
</div>
|
||||
|
||||
<div id="nav-path" class="navpath">
|
||||
<ul>
|
||||
<li class="navelem"><a class="el" href="dir_97aefd0d527b934f1d99a682da8fe6a9.html">lib</a></li><li class="navelem"><a class="el" href="dir_0f386e5012f166522d8afb320f99104b.html">PinChangeInt</a></li> </ul>
|
||||
</div>
|
||||
</div><!-- top -->
|
||||
<div class="header">
|
||||
<div class="summary">
|
||||
<a href="#nested-classes">Classes</a> |
|
||||
<a href="#define-members">Macros</a> |
|
||||
<a href="#typedef-members">Typedefs</a> </div>
|
||||
<div class="headertitle">
|
||||
<div class="title">PinChangeInt.h File Reference</div> </div>
|
||||
</div><!--header-->
|
||||
<div class="contents">
|
||||
<div class="textblock"><code>#include "WProgram.h"</code><br />
|
||||
<code>#include "<a class="el" href="PinChangeIntConfig_8h_source.html">PinChangeIntConfig.h</a>"</code><br />
|
||||
<code>#include "pins_arduino.h"</code><br />
|
||||
</div><div class="textblock"><div class="dynheader">
|
||||
Include dependency graph for PinChangeInt.h:</div>
|
||||
<div class="dyncontent">
|
||||
<div class="center"><img src="PinChangeInt_8h__incl.png" border="0" usemap="#alib_2PinChangeInt_2PinChangeInt_8h" alt=""/></div>
|
||||
<map name="alib_2PinChangeInt_2PinChangeInt_8h" id="alib_2PinChangeInt_2PinChangeInt_8h">
|
||||
<area shape="rect" title=" " alt="" coords="113,5,315,47"/>
|
||||
<area shape="rect" title=" " alt="" coords="5,95,108,121"/>
|
||||
<area shape="rect" href="PinChangeIntConfig_8h.html" title=" " alt="" coords="133,95,295,121"/>
|
||||
<area shape="rect" title=" " alt="" coords="319,95,437,121"/>
|
||||
</map>
|
||||
</div>
|
||||
</div><div class="textblock"><div class="dynheader">
|
||||
This graph shows which files directly or indirectly include this file:</div>
|
||||
<div class="dyncontent">
|
||||
<div class="center"><img src="PinChangeInt_8h__dep__incl.png" border="0" usemap="#alib_2PinChangeInt_2PinChangeInt_8hdep" alt=""/></div>
|
||||
<map name="alib_2PinChangeInt_2PinChangeInt_8hdep" id="alib_2PinChangeInt_2PinChangeInt_8hdep">
|
||||
<area shape="rect" title=" " alt="" coords="156,5,357,47"/>
|
||||
<area shape="rect" href="main_8cpp.html" title=" " alt="" coords="5,184,111,211"/>
|
||||
<area shape="rect" href="MotorWheel_8h.html" title=" " alt="" coords="149,102,365,129"/>
|
||||
<area shape="rect" href="PinChangeInt_8cpp.html" title=" " alt="" coords="389,95,591,136"/>
|
||||
<area shape="rect" href="UARTCom_8cpp.html" title=" " alt="" coords="135,184,378,211"/>
|
||||
<area shape="rect" href="UCommands_8cpp.html" title=" " alt="" coords="402,184,663,211"/>
|
||||
<area shape="rect" href="MotorWheel_8cpp.html" title=" " alt="" coords="688,184,919,211"/>
|
||||
</map>
|
||||
</div>
|
||||
</div>
|
||||
<p><a href="PinChangeInt_8h_source.html">Go to the source code of this file.</a></p>
|
||||
<table class="memberdecls">
|
||||
<tr class="heading"><td colspan="2"><h2 class="groupheader"><a name="nested-classes"></a>
|
||||
Classes</h2></td></tr>
|
||||
<tr class="memitem:"><td class="memItemLeft" align="right" valign="top">class  </td><td class="memItemRight" valign="bottom"><a class="el" href="classPCintPort.html">PCintPort</a></td></tr>
|
||||
<tr class="separator:"><td class="memSeparator" colspan="2"> </td></tr>
|
||||
<tr class="memitem:"><td class="memItemLeft" align="right" valign="top">class  </td><td class="memItemRight" valign="bottom"><a class="el" href="classPCintPort_1_1PCintPin.html">PCintPort::PCintPin</a></td></tr>
|
||||
<tr class="separator:"><td class="memSeparator" colspan="2"> </td></tr>
|
||||
</table><table class="memberdecls">
|
||||
<tr class="heading"><td colspan="2"><h2 class="groupheader"><a name="define-members"></a>
|
||||
Macros</h2></td></tr>
|
||||
<tr class="memitem:adc5e9b3687e8ad666a52ec695a69081c"><td class="memItemLeft" align="right" valign="top">#define </td><td class="memItemRight" valign="bottom"><a class="el" href="PinChangeInt_8h.html#adc5e9b3687e8ad666a52ec695a69081c">MAX_PIN_CHANGE_PINS</a>   8</td></tr>
|
||||
<tr class="separator:adc5e9b3687e8ad666a52ec695a69081c"><td class="memSeparator" colspan="2"> </td></tr>
|
||||
<tr class="memitem:affe455978cc6fe5b0cff09a1b93202c7"><td class="memItemLeft" align="right" valign="top">#define </td><td class="memItemRight" valign="bottom"><a class="el" href="PinChangeInt_8h.html#affe455978cc6fe5b0cff09a1b93202c7">INLINE_PCINT</a></td></tr>
|
||||
<tr class="separator:affe455978cc6fe5b0cff09a1b93202c7"><td class="memSeparator" colspan="2"> </td></tr>
|
||||
<tr class="memitem:a6b21b6a0a033a5a5c0ae3c07aa899a9f"><td class="memItemLeft" align="right" valign="top">#define </td><td class="memItemRight" valign="bottom"><a class="el" href="PinChangeInt_8h.html#a6b21b6a0a033a5a5c0ae3c07aa899a9f">PCdetachInterrupt</a>(pin)   <a class="el" href="classPCintPort.html#a7787c29d639bc6c1a30a14acb0f9fb9a">PCintPort::detachInterrupt</a>(pin)</td></tr>
|
||||
<tr class="separator:a6b21b6a0a033a5a5c0ae3c07aa899a9f"><td class="memSeparator" colspan="2"> </td></tr>
|
||||
<tr class="memitem:aa5908a22250605213e3874e2b0288a5d"><td class="memItemLeft" align="right" valign="top">#define </td><td class="memItemRight" valign="bottom"><a class="el" href="PinChangeInt_8h.html#aa5908a22250605213e3874e2b0288a5d">PCattachInterrupt</a>(pin, userFunc, mode)   <a class="el" href="classPCintPort.html#a8e6c9a8a860c39f6840a8b986c00e8d7">PCintPort::attachInterrupt</a>(pin, userFunc,mode)</td></tr>
|
||||
<tr class="separator:aa5908a22250605213e3874e2b0288a5d"><td class="memSeparator" colspan="2"> </td></tr>
|
||||
</table><table class="memberdecls">
|
||||
<tr class="heading"><td colspan="2"><h2 class="groupheader"><a name="typedef-members"></a>
|
||||
Typedefs</h2></td></tr>
|
||||
<tr class="memitem:a40b7734100b16d4ac170f568c7914d0a"><td class="memItemLeft" align="right" valign="top">typedef void(* </td><td class="memItemRight" valign="bottom"><a class="el" href="PinChangeInt_8h.html#a40b7734100b16d4ac170f568c7914d0a">PCIntvoidFuncPtr</a>) (void)</td></tr>
|
||||
<tr class="separator:a40b7734100b16d4ac170f568c7914d0a"><td class="memSeparator" colspan="2"> </td></tr>
|
||||
</table>
|
||||
<h2 class="groupheader">Macro Definition Documentation</h2>
|
||||
<a id="affe455978cc6fe5b0cff09a1b93202c7"></a>
|
||||
<h2 class="memtitle"><span class="permalink"><a href="#affe455978cc6fe5b0cff09a1b93202c7">◆ </a></span>INLINE_PCINT</h2>
|
||||
|
||||
<div class="memitem">
|
||||
<div class="memproto">
|
||||
<table class="memname">
|
||||
<tr>
|
||||
<td class="memname">#define INLINE_PCINT</td>
|
||||
</tr>
|
||||
</table>
|
||||
</div><div class="memdoc">
|
||||
|
||||
</div>
|
||||
</div>
|
||||
<a id="adc5e9b3687e8ad666a52ec695a69081c"></a>
|
||||
<h2 class="memtitle"><span class="permalink"><a href="#adc5e9b3687e8ad666a52ec695a69081c">◆ </a></span>MAX_PIN_CHANGE_PINS</h2>
|
||||
|
||||
<div class="memitem">
|
||||
<div class="memproto">
|
||||
<table class="memname">
|
||||
<tr>
|
||||
<td class="memname">#define MAX_PIN_CHANGE_PINS   8</td>
|
||||
</tr>
|
||||
</table>
|
||||
</div><div class="memdoc">
|
||||
|
||||
</div>
|
||||
</div>
|
||||
<a id="aa5908a22250605213e3874e2b0288a5d"></a>
|
||||
<h2 class="memtitle"><span class="permalink"><a href="#aa5908a22250605213e3874e2b0288a5d">◆ </a></span>PCattachInterrupt</h2>
|
||||
|
||||
<div class="memitem">
|
||||
<div class="memproto">
|
||||
<table class="memname">
|
||||
<tr>
|
||||
<td class="memname">#define PCattachInterrupt</td>
|
||||
<td>(</td>
|
||||
<td class="paramtype"> </td>
|
||||
<td class="paramname">pin, </td>
|
||||
</tr>
|
||||
<tr>
|
||||
<td class="paramkey"></td>
|
||||
<td></td>
|
||||
<td class="paramtype"> </td>
|
||||
<td class="paramname">userFunc, </td>
|
||||
</tr>
|
||||
<tr>
|
||||
<td class="paramkey"></td>
|
||||
<td></td>
|
||||
<td class="paramtype"> </td>
|
||||
<td class="paramname">mode </td>
|
||||
</tr>
|
||||
<tr>
|
||||
<td></td>
|
||||
<td>)</td>
|
||||
<td></td><td>   <a class="el" href="classPCintPort.html#a8e6c9a8a860c39f6840a8b986c00e8d7">PCintPort::attachInterrupt</a>(pin, userFunc,mode)</td>
|
||||
</tr>
|
||||
</table>
|
||||
</div><div class="memdoc">
|
||||
|
||||
</div>
|
||||
</div>
|
||||
<a id="a6b21b6a0a033a5a5c0ae3c07aa899a9f"></a>
|
||||
<h2 class="memtitle"><span class="permalink"><a href="#a6b21b6a0a033a5a5c0ae3c07aa899a9f">◆ </a></span>PCdetachInterrupt</h2>
|
||||
|
||||
<div class="memitem">
|
||||
<div class="memproto">
|
||||
<table class="memname">
|
||||
<tr>
|
||||
<td class="memname">#define PCdetachInterrupt</td>
|
||||
<td>(</td>
|
||||
<td class="paramtype"> </td>
|
||||
<td class="paramname">pin</td><td>)</td>
|
||||
<td>   <a class="el" href="classPCintPort.html#a7787c29d639bc6c1a30a14acb0f9fb9a">PCintPort::detachInterrupt</a>(pin)</td>
|
||||
</tr>
|
||||
</table>
|
||||
</div><div class="memdoc">
|
||||
|
||||
</div>
|
||||
</div>
|
||||
<h2 class="groupheader">Typedef Documentation</h2>
|
||||
<a id="a40b7734100b16d4ac170f568c7914d0a"></a>
|
||||
<h2 class="memtitle"><span class="permalink"><a href="#a40b7734100b16d4ac170f568c7914d0a">◆ </a></span>PCIntvoidFuncPtr</h2>
|
||||
|
||||
<div class="memitem">
|
||||
<div class="memproto">
|
||||
<table class="memname">
|
||||
<tr>
|
||||
<td class="memname">typedef void(* PCIntvoidFuncPtr) (void)</td>
|
||||
</tr>
|
||||
</table>
|
||||
</div><div class="memdoc">
|
||||
|
||||
</div>
|
||||
</div>
|
||||
</div><!-- contents -->
|
||||
<!-- start footer part -->
|
||||
<hr class="footer"/><address class="footer"><small>
|
||||
Generated by <a href="https://www.doxygen.org/index.html"><img class="footer" src="doxygen.svg" width="104" height="31" alt="doxygen"/></a> 1.9.1
|
||||
</small></address>
|
||||
</body>
|
||||
</html>
|
@ -1,9 +0,0 @@
|
||||
<map id="lib/PinChangeInt/PinChangeInt.h" name="lib/PinChangeInt/PinChangeInt.h">
|
||||
<area shape="rect" id="node1" title=" " alt="" coords="156,5,357,47"/>
|
||||
<area shape="rect" id="node2" href="$main_8cpp.html" title=" " alt="" coords="5,184,111,211"/>
|
||||
<area shape="rect" id="node3" href="$MotorWheel_8h.html" title=" " alt="" coords="149,102,365,129"/>
|
||||
<area shape="rect" id="node7" href="$PinChangeInt_8cpp.html" title=" " alt="" coords="389,95,591,136"/>
|
||||
<area shape="rect" id="node4" href="$UARTCom_8cpp.html" title=" " alt="" coords="135,184,378,211"/>
|
||||
<area shape="rect" id="node5" href="$UCommands_8cpp.html" title=" " alt="" coords="402,184,663,211"/>
|
||||
<area shape="rect" id="node6" href="$MotorWheel_8cpp.html" title=" " alt="" coords="688,184,919,211"/>
|
||||
</map>
|
@ -1 +0,0 @@
|
||||
d506b31cfddb00671b06c3e2c0add358
|
Before Width: | Height: | Size: 19 KiB |
@ -1,6 +0,0 @@
|
||||
<map id="lib/PinChangeInt/PinChangeInt.h" name="lib/PinChangeInt/PinChangeInt.h">
|
||||
<area shape="rect" id="node1" title=" " alt="" coords="113,5,315,47"/>
|
||||
<area shape="rect" id="node2" title=" " alt="" coords="5,95,108,121"/>
|
||||
<area shape="rect" id="node3" href="$PinChangeIntConfig_8h.html" title=" " alt="" coords="133,95,295,121"/>
|
||||
<area shape="rect" id="node4" title=" " alt="" coords="319,95,437,121"/>
|
||||
</map>
|
@ -1 +0,0 @@
|
||||
ceebaa8b25277ce6767ec680edbc2406
|
Before Width: | Height: | Size: 8.4 KiB |
@ -1,237 +0,0 @@
|
||||
<!DOCTYPE html PUBLIC "-//W3C//DTD XHTML 1.0 Transitional//EN" "https://www.w3.org/TR/xhtml1/DTD/xhtml1-transitional.dtd">
|
||||
<html xmlns="http://www.w3.org/1999/xhtml">
|
||||
<head>
|
||||
<meta http-equiv="Content-Type" content="text/xhtml;charset=UTF-8"/>
|
||||
<meta http-equiv="X-UA-Compatible" content="IE=9"/>
|
||||
<meta name="generator" content="Doxygen 1.9.1"/>
|
||||
<meta name="viewport" content="width=device-width, initial-scale=1"/>
|
||||
<title>DCAITI Robot Hardware: lib/PinChangeInt/PinChangeInt.h Source File</title>
|
||||
<link href="tabs.css" rel="stylesheet" type="text/css"/>
|
||||
<script type="text/javascript" src="jquery.js"></script>
|
||||
<script type="text/javascript" src="dynsections.js"></script>
|
||||
<link href="search/search.css" rel="stylesheet" type="text/css"/>
|
||||
<script type="text/javascript" src="search/searchdata.js"></script>
|
||||
<script type="text/javascript" src="search/search.js"></script>
|
||||
<link href="doxygen.css" rel="stylesheet" type="text/css" />
|
||||
</head>
|
||||
<body>
|
||||
<div id="top"><!-- do not remove this div, it is closed by doxygen! -->
|
||||
<div id="titlearea">
|
||||
<table cellspacing="0" cellpadding="0">
|
||||
<tbody>
|
||||
<tr style="height: 56px;">
|
||||
<td id="projectalign" style="padding-left: 0.5em;">
|
||||
<div id="projectname">DCAITI Robot Hardware
|
||||
 <span id="projectnumber">1.0</span>
|
||||
</div>
|
||||
</td>
|
||||
</tr>
|
||||
</tbody>
|
||||
</table>
|
||||
</div>
|
||||
<!-- end header part -->
|
||||
<!-- Generated by Doxygen 1.9.1 -->
|
||||
<script type="text/javascript">
|
||||
/* @license magnet:?xt=urn:btih:cf05388f2679ee054f2beb29a391d25f4e673ac3&dn=gpl-2.0.txt GPL-v2 */
|
||||
var searchBox = new SearchBox("searchBox", "search",false,'Search','.html');
|
||||
/* @license-end */
|
||||
</script>
|
||||
<script type="text/javascript" src="menudata.js"></script>
|
||||
<script type="text/javascript" src="menu.js"></script>
|
||||
<script type="text/javascript">
|
||||
/* @license magnet:?xt=urn:btih:cf05388f2679ee054f2beb29a391d25f4e673ac3&dn=gpl-2.0.txt GPL-v2 */
|
||||
$(function() {
|
||||
initMenu('',true,false,'search.php','Search');
|
||||
$(document).ready(function() { init_search(); });
|
||||
});
|
||||
/* @license-end */</script>
|
||||
<div id="main-nav"></div>
|
||||
<!-- window showing the filter options -->
|
||||
<div id="MSearchSelectWindow"
|
||||
onmouseover="return searchBox.OnSearchSelectShow()"
|
||||
onmouseout="return searchBox.OnSearchSelectHide()"
|
||||
onkeydown="return searchBox.OnSearchSelectKey(event)">
|
||||
</div>
|
||||
|
||||
<!-- iframe showing the search results (closed by default) -->
|
||||
<div id="MSearchResultsWindow">
|
||||
<iframe src="javascript:void(0)" frameborder="0"
|
||||
name="MSearchResults" id="MSearchResults">
|
||||
</iframe>
|
||||
</div>
|
||||
|
||||
<div id="nav-path" class="navpath">
|
||||
<ul>
|
||||
<li class="navelem"><a class="el" href="dir_97aefd0d527b934f1d99a682da8fe6a9.html">lib</a></li><li class="navelem"><a class="el" href="dir_0f386e5012f166522d8afb320f99104b.html">PinChangeInt</a></li> </ul>
|
||||
</div>
|
||||
</div><!-- top -->
|
||||
<div class="header">
|
||||
<div class="headertitle">
|
||||
<div class="title">PinChangeInt.h</div> </div>
|
||||
</div><!--header-->
|
||||
<div class="contents">
|
||||
<a href="PinChangeInt_8h.html">Go to the documentation of this file.</a><div class="fragment"><div class="line"><a name="l00001"></a><span class="lineno"> 1</span> <span class="comment">/*</span></div>
|
||||
<div class="line"><a name="l00002"></a><span class="lineno"> 2</span> <span class="comment"> PinChangeInt.h</span></div>
|
||||
<div class="line"><a name="l00003"></a><span class="lineno"> 3</span> <span class="comment">*/</span></div>
|
||||
<div class="line"><a name="l00004"></a><span class="lineno"> 4</span>  </div>
|
||||
<div class="line"><a name="l00005"></a><span class="lineno"> 5</span>  </div>
|
||||
<div class="line"><a name="l00006"></a><span class="lineno"> 6</span> <span class="preprocessor">#ifndef PinChangeInt_h</span></div>
|
||||
<div class="line"><a name="l00007"></a><span class="lineno"> 7</span> <span class="preprocessor">#define PinChangeInt_h</span></div>
|
||||
<div class="line"><a name="l00008"></a><span class="lineno"> 8</span>  </div>
|
||||
<div class="line"><a name="l00009"></a><span class="lineno"> 9</span> <span class="preprocessor">#if defined(ARDUINO) && ARDUINO >= 100</span></div>
|
||||
<div class="line"><a name="l00010"></a><span class="lineno"> 10</span> <span class="preprocessor">#include "Arduino.h"</span></div>
|
||||
<div class="line"><a name="l00011"></a><span class="lineno"> 11</span> <span class="preprocessor">#else</span></div>
|
||||
<div class="line"><a name="l00012"></a><span class="lineno"> 12</span> <span class="preprocessor">#include "WProgram.h"</span></div>
|
||||
<div class="line"><a name="l00013"></a><span class="lineno"> 13</span> <span class="preprocessor">#endif</span></div>
|
||||
<div class="line"><a name="l00014"></a><span class="lineno"> 14</span>  </div>
|
||||
<div class="line"><a name="l00015"></a><span class="lineno"> 15</span> <span class="preprocessor">#include "<a class="code" href="PinChangeIntConfig_8h.html">PinChangeIntConfig.h</a>"</span></div>
|
||||
<div class="line"><a name="l00016"></a><span class="lineno"> 16</span> <span class="preprocessor">#ifndef Pins_Arduino_h</span></div>
|
||||
<div class="line"><a name="l00017"></a><span class="lineno"> 17</span> <span class="preprocessor">#include "pins_arduino.h"</span></div>
|
||||
<div class="line"><a name="l00018"></a><span class="lineno"> 18</span> <span class="preprocessor">#endif</span></div>
|
||||
<div class="line"><a name="l00019"></a><span class="lineno"> 19</span> <span class="comment">// This library was inspired by and derived from "johnboiles" (it seems) Main.PCInt Arduino Playground example</span></div>
|
||||
<div class="line"><a name="l00020"></a><span class="lineno"> 20</span> <span class="comment">// see: http://www.arduino.cc/playground/Main/PcInt</span></div>
|
||||
<div class="line"><a name="l00021"></a><span class="lineno"> 21</span>  </div>
|
||||
<div class="line"><a name="l00022"></a><span class="lineno"> 22</span>  </div>
|
||||
<div class="line"><a name="l00023"></a><span class="lineno"> 23</span> <span class="comment">// Interrupt management for PCI</span></div>
|
||||
<div class="line"><a name="l00024"></a><span class="lineno"> 24</span> <span class="comment">/*</span></div>
|
||||
<div class="line"><a name="l00025"></a><span class="lineno"> 25</span> <span class="comment"> * an extension to the interrupt support for arduino.</span></div>
|
||||
<div class="line"><a name="l00026"></a><span class="lineno"> 26</span> <span class="comment"> * add pin change interrupts to the external interrupts, giving a way</span></div>
|
||||
<div class="line"><a name="l00027"></a><span class="lineno"> 27</span> <span class="comment"> * for users to have interrupts drive off of any pin.</span></div>
|
||||
<div class="line"><a name="l00028"></a><span class="lineno"> 28</span> <span class="comment"> * Refer to avr-gcc header files, arduino source and atmega datasheet.</span></div>
|
||||
<div class="line"><a name="l00029"></a><span class="lineno"> 29</span> <span class="comment"> */</span></div>
|
||||
<div class="line"><a name="l00030"></a><span class="lineno"> 30</span>  </div>
|
||||
<div class="line"><a name="l00031"></a><span class="lineno"> 31</span> <span class="comment">/*</span></div>
|
||||
<div class="line"><a name="l00032"></a><span class="lineno"> 32</span> <span class="comment"> * Theory: all IO pins on AtmegaX(168/328/1280/2560) are covered by Pin Change Interrupts.</span></div>
|
||||
<div class="line"><a name="l00033"></a><span class="lineno"> 33</span> <span class="comment"> * The PCINT corresponding to the pin must be enabled and masked, and</span></div>
|
||||
<div class="line"><a name="l00034"></a><span class="lineno"> 34</span> <span class="comment"> * an ISR routine provided. Since PCINTs are per port, not per pin, the ISR</span></div>
|
||||
<div class="line"><a name="l00035"></a><span class="lineno"> 35</span> <span class="comment"> * must use some logic to actually implement a per-pin interrupt service.</span></div>
|
||||
<div class="line"><a name="l00036"></a><span class="lineno"> 36</span> <span class="comment"> */</span></div>
|
||||
<div class="line"><a name="l00037"></a><span class="lineno"> 37</span>  </div>
|
||||
<div class="line"><a name="l00038"></a><span class="lineno"> 38</span> <span class="comment">/* Pin to interrupt map ON ATmega168/328:</span></div>
|
||||
<div class="line"><a name="l00039"></a><span class="lineno"> 39</span> <span class="comment"> * D0-D7 = PCINT 16-23 = PCIR2 = PD = PCIE2 = pcmsk2</span></div>
|
||||
<div class="line"><a name="l00040"></a><span class="lineno"> 40</span> <span class="comment"> * D8-D13 = PCINT 0-5 = PCIR0 = PB = PCIE0 = pcmsk0</span></div>
|
||||
<div class="line"><a name="l00041"></a><span class="lineno"> 41</span> <span class="comment"> * A0-A5 (D14-D19) = PCINT 8-13 = PCIR1 = PC = PCIE1 = pcmsk1</span></div>
|
||||
<div class="line"><a name="l00042"></a><span class="lineno"> 42</span> <span class="comment"> */</span></div>
|
||||
<div class="line"><a name="l00043"></a><span class="lineno"> 43</span>  </div>
|
||||
<div class="line"><a name="l00044"></a><span class="lineno"> 44</span>  </div>
|
||||
<div class="line"><a name="l00045"></a><span class="lineno"> 45</span> <span class="comment">/* Pin to interrupt map ON ATmega1280/2560:</span></div>
|
||||
<div class="line"><a name="l00046"></a><span class="lineno"> 46</span> <span class="comment"> * D50-D53 = PCINT 3-0 = PCIR0 = PB = PCIE0 = pcmsk0</span></div>
|
||||
<div class="line"><a name="l00047"></a><span class="lineno"> 47</span> <span class="comment"> * D10-D13 = PCINT 4-7 = PCIR0 = PB = PCIE0 = pcmsk0</span></div>
|
||||
<div class="line"><a name="l00048"></a><span class="lineno"> 48</span> <span class="comment"> * A8-A15 (D62-D69) = PCINT 16-23 = PCIR2 = Pk = PCIE2 = pcmsk2</span></div>
|
||||
<div class="line"><a name="l00049"></a><span class="lineno"> 49</span> <span class="comment"> </span></div>
|
||||
<div class="line"><a name="l00050"></a><span class="lineno"> 50</span> <span class="comment"> * *******D0 = PCINT 8 = PCIR1 = PE = PCIE1 = pcmsk1**********</span></div>
|
||||
<div class="line"><a name="l00051"></a><span class="lineno"> 51</span> <span class="comment"> * *******D14-D15 = PCINT 10-9 = PJ = PCIE1 = pcmsk1*********</span></div>
|
||||
<div class="line"><a name="l00052"></a><span class="lineno"> 52</span> <span class="comment"> ********NOTE:PCINT 8-15 does NOT available in this library******</span></div>
|
||||
<div class="line"><a name="l00053"></a><span class="lineno"> 53</span> <span class="comment"> */</span></div>
|
||||
<div class="line"><a name="l00054"></a><span class="lineno"> 54</span>  </div>
|
||||
<div class="line"><a name="l00055"></a><span class="lineno"> 55</span>  </div>
|
||||
<div class="line"><a name="l00056"></a><span class="lineno"> 56</span> <span class="comment">/*</span></div>
|
||||
<div class="line"><a name="l00057"></a><span class="lineno"> 57</span> <span class="comment"> Please make any configuration changes in the accompanying PinChangeIntConfig.h file.</span></div>
|
||||
<div class="line"><a name="l00058"></a><span class="lineno"> 58</span> <span class="comment"> This will help avoid having to reset your config in the event of changes to the </span></div>
|
||||
<div class="line"><a name="l00059"></a><span class="lineno"> 59</span> <span class="comment"> library code (just don't replace that file when you update).</span></div>
|
||||
<div class="line"><a name="l00060"></a><span class="lineno"> 60</span> <span class="comment"></span> </div>
|
||||
<div class="line"><a name="l00061"></a><span class="lineno"> 61</span> <span class="comment">*/</span></div>
|
||||
<div class="line"><a name="l00062"></a><span class="lineno"> 62</span>  </div>
|
||||
<div class="line"><a name="l00063"></a><span class="lineno"> 63</span>  </div>
|
||||
<div class="line"><a name="l00064"></a><span class="lineno"> 64</span> <span class="preprocessor">#ifndef MAX_PIN_CHANGE_PINS</span></div>
|
||||
<div class="line"><a name="l00065"></a><span class="lineno"><a class="line" href="PinChangeInt_8h.html#adc5e9b3687e8ad666a52ec695a69081c"> 65</a></span> <span class="preprocessor">#define MAX_PIN_CHANGE_PINS 8</span></div>
|
||||
<div class="line"><a name="l00066"></a><span class="lineno"> 66</span> <span class="preprocessor">#endif</span></div>
|
||||
<div class="line"><a name="l00067"></a><span class="lineno"> 67</span>  </div>
|
||||
<div class="line"><a name="l00068"></a><span class="lineno"> 68</span> <span class="comment">// You can reduce the memory footprint of this handler by declaring that there will be no pin change interrupts</span></div>
|
||||
<div class="line"><a name="l00069"></a><span class="lineno"> 69</span> <span class="comment">// on any of the three ports.</span></div>
|
||||
<div class="line"><a name="l00070"></a><span class="lineno"> 70</span> <span class="comment">// define NO_PORTB_PINCHANGES to indicate that port b will not be used for pin change interrupts</span></div>
|
||||
<div class="line"><a name="l00071"></a><span class="lineno"> 71</span> <span class="comment">// define NO_PORTC_PINCHANGES to indicate that port c will not be used for pin change interrupts</span></div>
|
||||
<div class="line"><a name="l00072"></a><span class="lineno"> 72</span> <span class="comment">// define NO_PORTD_PINCHANGES to indicate that port d will not be used for pin change interrupts</span></div>
|
||||
<div class="line"><a name="l00073"></a><span class="lineno"> 73</span> <span class="comment">// If only a single port remains, the handler will be declared inline reducing the size and latency </span></div>
|
||||
<div class="line"><a name="l00074"></a><span class="lineno"> 74</span> <span class="comment">// of the handler.</span></div>
|
||||
<div class="line"><a name="l00075"></a><span class="lineno"> 75</span>  </div>
|
||||
<div class="line"><a name="l00076"></a><span class="lineno"> 76</span> <span class="comment">// if their is only one PCInt vector in use the code can be inlined</span></div>
|
||||
<div class="line"><a name="l00077"></a><span class="lineno"> 77</span> <span class="comment">// reducing latecncy and code size</span></div>
|
||||
<div class="line"><a name="l00078"></a><span class="lineno"><a class="line" href="PinChangeInt_8h.html#affe455978cc6fe5b0cff09a1b93202c7"> 78</a></span> <span class="preprocessor">#define INLINE_PCINT</span></div>
|
||||
<div class="line"><a name="l00079"></a><span class="lineno"> 79</span> <span class="preprocessor">#if ((defined(NO_PORTB_PINCHANGES) && defined(NO_PORTC_PINCHANGES)) || \</span></div>
|
||||
<div class="line"><a name="l00080"></a><span class="lineno"> 80</span> <span class="preprocessor"> (defined(NO_PORTC_PINCHANGES) && defined(NO_PORTD_PINCHANGES)) || \</span></div>
|
||||
<div class="line"><a name="l00081"></a><span class="lineno"> 81</span> <span class="preprocessor"> (defined(NO_PORTD_PINCHANGES) && defined(NO_PORTB_PINCHANGES)))</span></div>
|
||||
<div class="line"><a name="l00082"></a><span class="lineno"> 82</span> <span class="preprocessor">#undef INLINE_PCINT</span></div>
|
||||
<div class="line"><a name="l00083"></a><span class="lineno"> 83</span> <span class="preprocessor">#define INLINE_PCINT inline</span></div>
|
||||
<div class="line"><a name="l00084"></a><span class="lineno"> 84</span> <span class="preprocessor">#endif</span></div>
|
||||
<div class="line"><a name="l00085"></a><span class="lineno"> 85</span>  </div>
|
||||
<div class="line"><a name="l00086"></a><span class="lineno"> 86</span> <span class="comment">// Provide drop in compatibility with johnboiles PCInt project at</span></div>
|
||||
<div class="line"><a name="l00087"></a><span class="lineno"> 87</span> <span class="comment">// http://www.arduino.cc/playground/Main/PcInt</span></div>
|
||||
<div class="line"><a name="l00088"></a><span class="lineno"><a class="line" href="PinChangeInt_8h.html#a6b21b6a0a033a5a5c0ae3c07aa899a9f"> 88</a></span> <span class="preprocessor">#define PCdetachInterrupt(pin) PCintPort::detachInterrupt(pin)</span></div>
|
||||
<div class="line"><a name="l00089"></a><span class="lineno"><a class="line" href="PinChangeInt_8h.html#aa5908a22250605213e3874e2b0288a5d"> 89</a></span> <span class="preprocessor">#define PCattachInterrupt(pin,userFunc,mode) PCintPort::attachInterrupt(pin, userFunc,mode)</span></div>
|
||||
<div class="line"><a name="l00090"></a><span class="lineno"> 90</span>  </div>
|
||||
<div class="line"><a name="l00091"></a><span class="lineno"> 91</span>  </div>
|
||||
<div class="line"><a name="l00092"></a><span class="lineno"> 92</span>  </div>
|
||||
<div class="line"><a name="l00093"></a><span class="lineno"><a class="line" href="PinChangeInt_8h.html#a40b7734100b16d4ac170f568c7914d0a"> 93</a></span> <span class="keyword">typedef</span> void (*<a class="code" href="PinChangeInt_8h.html#a40b7734100b16d4ac170f568c7914d0a">PCIntvoidFuncPtr</a>)(void);</div>
|
||||
<div class="line"><a name="l00094"></a><span class="lineno"> 94</span>  </div>
|
||||
<div class="line"><a name="l00095"></a><span class="lineno"><a class="line" href="classPCintPort.html"> 95</a></span> <span class="keyword">class </span><a class="code" href="classPCintPort.html">PCintPort</a> {</div>
|
||||
<div class="line"><a name="l00096"></a><span class="lineno"> 96</span>  <a class="code" href="classPCintPort.html">PCintPort</a>(<span class="keywordtype">int</span> index,<span class="keyword">volatile</span> uint8_t& maskReg) :</div>
|
||||
<div class="line"><a name="l00097"></a><span class="lineno"> 97</span> <span class="preprocessor"> #if defined(__AVR_ATmega1280__) || defined(__AVR_ATmega2560__)</span></div>
|
||||
<div class="line"><a name="l00098"></a><span class="lineno"> 98</span>  <a class="code" href="classPCintPort.html#ab36a9f3ef148411101704f3723d5cd0d">portInputReg</a>(*portInputRegister((index == 0)?(2):(index + 9))),</div>
|
||||
<div class="line"><a name="l00099"></a><span class="lineno"> 99</span>  </div>
|
||||
<div class="line"><a name="l00100"></a><span class="lineno"> 100</span> <span class="preprocessor"> #else</span></div>
|
||||
<div class="line"><a name="l00101"></a><span class="lineno"> 101</span>  <a class="code" href="classPCintPort.html#ab36a9f3ef148411101704f3723d5cd0d">portInputReg</a>(*portInputRegister(index + 2)),</div>
|
||||
<div class="line"><a name="l00102"></a><span class="lineno"> 102</span> <span class="preprocessor"> #endif</span></div>
|
||||
<div class="line"><a name="l00103"></a><span class="lineno"> 103</span>  </div>
|
||||
<div class="line"><a name="l00104"></a><span class="lineno"> 104</span>  <a class="code" href="classPCintPort.html#abe34a54a1b1bd8b2404b9227b55147fb">pcmask</a>(maskReg),</div>
|
||||
<div class="line"><a name="l00105"></a><span class="lineno"> 105</span>  <a class="code" href="classPCintPort.html#ab817a0637b722922c5d3cafc0dfd52d7">PCICRbit</a>(1 << index),</div>
|
||||
<div class="line"><a name="l00106"></a><span class="lineno"> 106</span>  <a class="code" href="classPCintPort.html#a955b8648c929952a8444656276e1b6ef">PCintLast</a>(0) {</div>
|
||||
<div class="line"><a name="l00107"></a><span class="lineno"> 107</span>  <span class="keywordflow">for</span> (<span class="keywordtype">int</span> i = 0; i < 9; i++) {</div>
|
||||
<div class="line"><a name="l00108"></a><span class="lineno"> 108</span>  <a class="code" href="classPCintPort.html#a068bde359af5d3567e4d031d9ac9c655">pcIntPins</a>[i] = NULL;</div>
|
||||
<div class="line"><a name="l00109"></a><span class="lineno"> 109</span>  }</div>
|
||||
<div class="line"><a name="l00110"></a><span class="lineno"> 110</span>  }</div>
|
||||
<div class="line"><a name="l00111"></a><span class="lineno"> 111</span> <span class="keyword">public</span>:</div>
|
||||
<div class="line"><a name="l00112"></a><span class="lineno"> 112</span>  <span class="keyword">static</span> <span class="keywordtype">void</span> <a class="code" href="classPCintPort.html#a8e6c9a8a860c39f6840a8b986c00e8d7">attachInterrupt</a>(uint8_t pin, <a class="code" href="PinChangeInt_8h.html#a40b7734100b16d4ac170f568c7914d0a">PCIntvoidFuncPtr</a> userFunc, <span class="keywordtype">int</span> mode);</div>
|
||||
<div class="line"><a name="l00113"></a><span class="lineno"> 113</span>  <span class="keyword">static</span> <span class="keywordtype">void</span> <a class="code" href="classPCintPort.html#a7787c29d639bc6c1a30a14acb0f9fb9a">detachInterrupt</a>(uint8_t pin);</div>
|
||||
<div class="line"><a name="l00114"></a><span class="lineno"> 114</span>  <a class="code" href="PinChangeInt_8h.html#affe455978cc6fe5b0cff09a1b93202c7">INLINE_PCINT</a> <span class="keywordtype">void</span> <a class="code" href="classPCintPort.html#a576bbb5d4190a7af0de2528760933916">PCint</a>();</div>
|
||||
<div class="line"><a name="l00115"></a><span class="lineno"><a class="line" href="classPCintPort.html#a9d5cdcb0bddf88489fccb288be9ebf3e"> 115</a></span>  <span class="keyword">static</span> <a class="code" href="classPCintPort.html">PCintPort</a> <a class="code" href="classPCintPort.html#a9d5cdcb0bddf88489fccb288be9ebf3e">pcIntPorts</a>[];</div>
|
||||
<div class="line"><a name="l00116"></a><span class="lineno"> 116</span>  </div>
|
||||
<div class="line"><a name="l00117"></a><span class="lineno"> 117</span> <span class="keyword">protected</span>:</div>
|
||||
<div class="line"><a name="l00118"></a><span class="lineno"><a class="line" href="classPCintPort_1_1PCintPin.html"> 118</a></span>  <span class="keyword">class </span><a class="code" href="classPCintPort_1_1PCintPin.html">PCintPin</a> {</div>
|
||||
<div class="line"><a name="l00119"></a><span class="lineno"> 119</span>  <span class="keyword">public</span>:</div>
|
||||
<div class="line"><a name="l00120"></a><span class="lineno"><a class="line" href="classPCintPort_1_1PCintPin.html#a042bb6da7549a825e4c0231af7079533"> 120</a></span>  <a class="code" href="classPCintPort_1_1PCintPin.html#a042bb6da7549a825e4c0231af7079533">PCintPin</a>() :</div>
|
||||
<div class="line"><a name="l00121"></a><span class="lineno"> 121</span>  <a class="code" href="classPCintPort_1_1PCintPin.html#a5f1750440a39afc1e0b7ec885bd90282">PCintFunc</a>((<a class="code" href="PinChangeInt_8h.html#a40b7734100b16d4ac170f568c7914d0a">PCIntvoidFuncPtr</a>)NULL),</div>
|
||||
<div class="line"><a name="l00122"></a><span class="lineno"> 122</span>  <a class="code" href="classPCintPort_1_1PCintPin.html#aded6dbbea2aa1ebd77133332b3c98556">PCintMode</a>(0) {}</div>
|
||||
<div class="line"><a name="l00123"></a><span class="lineno"><a class="line" href="classPCintPort_1_1PCintPin.html#a5f1750440a39afc1e0b7ec885bd90282"> 123</a></span>  <a class="code" href="PinChangeInt_8h.html#a40b7734100b16d4ac170f568c7914d0a">PCIntvoidFuncPtr</a> <a class="code" href="classPCintPort_1_1PCintPin.html#a5f1750440a39afc1e0b7ec885bd90282">PCintFunc</a>;</div>
|
||||
<div class="line"><a name="l00124"></a><span class="lineno"><a class="line" href="classPCintPort_1_1PCintPin.html#aded6dbbea2aa1ebd77133332b3c98556"> 124</a></span>  uint8_t <a class="code" href="classPCintPort_1_1PCintPin.html#aded6dbbea2aa1ebd77133332b3c98556">PCintMode</a>;</div>
|
||||
<div class="line"><a name="l00125"></a><span class="lineno"><a class="line" href="classPCintPort_1_1PCintPin.html#aec2baaa5bc8af4f7f3310bae39e8304c"> 125</a></span>  uint8_t <a class="code" href="classPCintPort_1_1PCintPin.html#aec2baaa5bc8af4f7f3310bae39e8304c">PCIntMask</a>;</div>
|
||||
<div class="line"><a name="l00126"></a><span class="lineno"><a class="line" href="classPCintPort_1_1PCintPin.html#a934bbc672c5e9faa448477ecb93c7955"> 126</a></span>  <span class="keyword">static</span> <a class="code" href="classPCintPort_1_1PCintPin.html">PCintPin</a> <a class="code" href="classPCintPort_1_1PCintPin.html#a934bbc672c5e9faa448477ecb93c7955">pinDataAlloc</a>[<a class="code" href="PinChangeInt_8h.html#adc5e9b3687e8ad666a52ec695a69081c">MAX_PIN_CHANGE_PINS</a>];</div>
|
||||
<div class="line"><a name="l00127"></a><span class="lineno"> 127</span>  };</div>
|
||||
<div class="line"><a name="l00128"></a><span class="lineno"> 128</span>  <span class="keywordtype">void</span> <a class="code" href="classPCintPort.html#a68db5c9fc10ce5d054c4184dbd00adeb">addPin</a>(uint8_t mode,uint8_t mask,<a class="code" href="PinChangeInt_8h.html#a40b7734100b16d4ac170f568c7914d0a">PCIntvoidFuncPtr</a> userFunc);</div>
|
||||
<div class="line"><a name="l00129"></a><span class="lineno"> 129</span>  <span class="keywordtype">void</span> <a class="code" href="classPCintPort.html#afecea645c5a79b54eab38b11c8ba19a6">delPin</a>(uint8_t mask);</div>
|
||||
<div class="line"><a name="l00130"></a><span class="lineno"><a class="line" href="classPCintPort.html#ab36a9f3ef148411101704f3723d5cd0d"> 130</a></span>  <span class="keyword">volatile</span> uint8_t& <a class="code" href="classPCintPort.html#ab36a9f3ef148411101704f3723d5cd0d">portInputReg</a>;</div>
|
||||
<div class="line"><a name="l00131"></a><span class="lineno"><a class="line" href="classPCintPort.html#abe34a54a1b1bd8b2404b9227b55147fb"> 131</a></span>  <span class="keyword">volatile</span> uint8_t& <a class="code" href="classPCintPort.html#abe34a54a1b1bd8b2404b9227b55147fb">pcmask</a>;</div>
|
||||
<div class="line"><a name="l00132"></a><span class="lineno"><a class="line" href="classPCintPort.html#ab817a0637b722922c5d3cafc0dfd52d7"> 132</a></span>  <span class="keyword">const</span> uint8_t <a class="code" href="classPCintPort.html#ab817a0637b722922c5d3cafc0dfd52d7">PCICRbit</a>;</div>
|
||||
<div class="line"><a name="l00133"></a><span class="lineno"><a class="line" href="classPCintPort.html#a955b8648c929952a8444656276e1b6ef"> 133</a></span>  uint8_t <a class="code" href="classPCintPort.html#a955b8648c929952a8444656276e1b6ef">PCintLast</a>;</div>
|
||||
<div class="line"><a name="l00134"></a><span class="lineno"><a class="line" href="classPCintPort.html#a068bde359af5d3567e4d031d9ac9c655"> 134</a></span>  <a class="code" href="classPCintPort_1_1PCintPin.html">PCintPin</a>* <a class="code" href="classPCintPort.html#a068bde359af5d3567e4d031d9ac9c655">pcIntPins</a>[9]; <span class="comment">// extra entry is a barrier</span></div>
|
||||
<div class="line"><a name="l00135"></a><span class="lineno"> 135</span> };</div>
|
||||
<div class="line"><a name="l00136"></a><span class="lineno"> 136</span> <span class="preprocessor">#endif</span></div>
|
||||
<div class="ttc" id="aPinChangeIntConfig_8h_html"><div class="ttname"><a href="PinChangeIntConfig_8h.html">PinChangeIntConfig.h</a></div></div>
|
||||
<div class="ttc" id="aPinChangeInt_8h_html_a40b7734100b16d4ac170f568c7914d0a"><div class="ttname"><a href="PinChangeInt_8h.html#a40b7734100b16d4ac170f568c7914d0a">PCIntvoidFuncPtr</a></div><div class="ttdeci">void(* PCIntvoidFuncPtr)(void)</div><div class="ttdef"><b>Definition:</b> PinChangeInt.h:93</div></div>
|
||||
<div class="ttc" id="aPinChangeInt_8h_html_adc5e9b3687e8ad666a52ec695a69081c"><div class="ttname"><a href="PinChangeInt_8h.html#adc5e9b3687e8ad666a52ec695a69081c">MAX_PIN_CHANGE_PINS</a></div><div class="ttdeci">#define MAX_PIN_CHANGE_PINS</div><div class="ttdef"><b>Definition:</b> PinChangeInt.h:65</div></div>
|
||||
<div class="ttc" id="aPinChangeInt_8h_html_affe455978cc6fe5b0cff09a1b93202c7"><div class="ttname"><a href="PinChangeInt_8h.html#affe455978cc6fe5b0cff09a1b93202c7">INLINE_PCINT</a></div><div class="ttdeci">#define INLINE_PCINT</div><div class="ttdef"><b>Definition:</b> PinChangeInt.h:78</div></div>
|
||||
<div class="ttc" id="aclassPCintPort_1_1PCintPin_html"><div class="ttname"><a href="classPCintPort_1_1PCintPin.html">PCintPort::PCintPin</a></div><div class="ttdef"><b>Definition:</b> PinChangeInt.h:118</div></div>
|
||||
<div class="ttc" id="aclassPCintPort_1_1PCintPin_html_a042bb6da7549a825e4c0231af7079533"><div class="ttname"><a href="classPCintPort_1_1PCintPin.html#a042bb6da7549a825e4c0231af7079533">PCintPort::PCintPin::PCintPin</a></div><div class="ttdeci">PCintPin()</div><div class="ttdef"><b>Definition:</b> PinChangeInt.h:120</div></div>
|
||||
<div class="ttc" id="aclassPCintPort_1_1PCintPin_html_a5f1750440a39afc1e0b7ec885bd90282"><div class="ttname"><a href="classPCintPort_1_1PCintPin.html#a5f1750440a39afc1e0b7ec885bd90282">PCintPort::PCintPin::PCintFunc</a></div><div class="ttdeci">PCIntvoidFuncPtr PCintFunc</div><div class="ttdef"><b>Definition:</b> PinChangeInt.h:123</div></div>
|
||||
<div class="ttc" id="aclassPCintPort_1_1PCintPin_html_a934bbc672c5e9faa448477ecb93c7955"><div class="ttname"><a href="classPCintPort_1_1PCintPin.html#a934bbc672c5e9faa448477ecb93c7955">PCintPort::PCintPin::pinDataAlloc</a></div><div class="ttdeci">static PCintPin pinDataAlloc[MAX_PIN_CHANGE_PINS]</div><div class="ttdef"><b>Definition:</b> PinChangeInt.h:126</div></div>
|
||||
<div class="ttc" id="aclassPCintPort_1_1PCintPin_html_aded6dbbea2aa1ebd77133332b3c98556"><div class="ttname"><a href="classPCintPort_1_1PCintPin.html#aded6dbbea2aa1ebd77133332b3c98556">PCintPort::PCintPin::PCintMode</a></div><div class="ttdeci">uint8_t PCintMode</div><div class="ttdef"><b>Definition:</b> PinChangeInt.h:124</div></div>
|
||||
<div class="ttc" id="aclassPCintPort_1_1PCintPin_html_aec2baaa5bc8af4f7f3310bae39e8304c"><div class="ttname"><a href="classPCintPort_1_1PCintPin.html#aec2baaa5bc8af4f7f3310bae39e8304c">PCintPort::PCintPin::PCIntMask</a></div><div class="ttdeci">uint8_t PCIntMask</div><div class="ttdef"><b>Definition:</b> PinChangeInt.h:125</div></div>
|
||||
<div class="ttc" id="aclassPCintPort_html"><div class="ttname"><a href="classPCintPort.html">PCintPort</a></div><div class="ttdef"><b>Definition:</b> PinChangeInt.h:95</div></div>
|
||||
<div class="ttc" id="aclassPCintPort_html_a068bde359af5d3567e4d031d9ac9c655"><div class="ttname"><a href="classPCintPort.html#a068bde359af5d3567e4d031d9ac9c655">PCintPort::pcIntPins</a></div><div class="ttdeci">PCintPin * pcIntPins[9]</div><div class="ttdef"><b>Definition:</b> PinChangeInt.h:134</div></div>
|
||||
<div class="ttc" id="aclassPCintPort_html_a576bbb5d4190a7af0de2528760933916"><div class="ttname"><a href="classPCintPort.html#a576bbb5d4190a7af0de2528760933916">PCintPort::PCint</a></div><div class="ttdeci">INLINE_PCINT void PCint()</div><div class="ttdef"><b>Definition:</b> PinChangeInt.cpp:139</div></div>
|
||||
<div class="ttc" id="aclassPCintPort_html_a68db5c9fc10ce5d054c4184dbd00adeb"><div class="ttname"><a href="classPCintPort.html#a68db5c9fc10ce5d054c4184dbd00adeb">PCintPort::addPin</a></div><div class="ttdeci">void addPin(uint8_t mode, uint8_t mask, PCIntvoidFuncPtr userFunc)</div><div class="ttdef"><b>Definition:</b> PinChangeInt.cpp:17</div></div>
|
||||
<div class="ttc" id="aclassPCintPort_html_a7787c29d639bc6c1a30a14acb0f9fb9a"><div class="ttname"><a href="classPCintPort.html#a7787c29d639bc6c1a30a14acb0f9fb9a">PCintPort::detachInterrupt</a></div><div class="ttdeci">static void detachInterrupt(uint8_t pin)</div><div class="ttdef"><b>Definition:</b> PinChangeInt.cpp:115</div></div>
|
||||
<div class="ttc" id="aclassPCintPort_html_a8e6c9a8a860c39f6840a8b986c00e8d7"><div class="ttname"><a href="classPCintPort.html#a8e6c9a8a860c39f6840a8b986c00e8d7">PCintPort::attachInterrupt</a></div><div class="ttdeci">static void attachInterrupt(uint8_t pin, PCIntvoidFuncPtr userFunc, int mode)</div><div class="ttdef"><b>Definition:</b> PinChangeInt.cpp:81</div></div>
|
||||
<div class="ttc" id="aclassPCintPort_html_a955b8648c929952a8444656276e1b6ef"><div class="ttname"><a href="classPCintPort.html#a955b8648c929952a8444656276e1b6ef">PCintPort::PCintLast</a></div><div class="ttdeci">uint8_t PCintLast</div><div class="ttdef"><b>Definition:</b> PinChangeInt.h:133</div></div>
|
||||
<div class="ttc" id="aclassPCintPort_html_a9d5cdcb0bddf88489fccb288be9ebf3e"><div class="ttname"><a href="classPCintPort.html#a9d5cdcb0bddf88489fccb288be9ebf3e">PCintPort::pcIntPorts</a></div><div class="ttdeci">static PCintPort pcIntPorts[]</div><div class="ttdef"><b>Definition:</b> PinChangeInt.h:115</div></div>
|
||||
<div class="ttc" id="aclassPCintPort_html_ab36a9f3ef148411101704f3723d5cd0d"><div class="ttname"><a href="classPCintPort.html#ab36a9f3ef148411101704f3723d5cd0d">PCintPort::portInputReg</a></div><div class="ttdeci">volatile uint8_t & portInputReg</div><div class="ttdef"><b>Definition:</b> PinChangeInt.h:130</div></div>
|
||||
<div class="ttc" id="aclassPCintPort_html_ab817a0637b722922c5d3cafc0dfd52d7"><div class="ttname"><a href="classPCintPort.html#ab817a0637b722922c5d3cafc0dfd52d7">PCintPort::PCICRbit</a></div><div class="ttdeci">const uint8_t PCICRbit</div><div class="ttdef"><b>Definition:</b> PinChangeInt.h:132</div></div>
|
||||
<div class="ttc" id="aclassPCintPort_html_abe34a54a1b1bd8b2404b9227b55147fb"><div class="ttname"><a href="classPCintPort.html#abe34a54a1b1bd8b2404b9227b55147fb">PCintPort::pcmask</a></div><div class="ttdeci">volatile uint8_t & pcmask</div><div class="ttdef"><b>Definition:</b> PinChangeInt.h:131</div></div>
|
||||
<div class="ttc" id="aclassPCintPort_html_afecea645c5a79b54eab38b11c8ba19a6"><div class="ttname"><a href="classPCintPort.html#afecea645c5a79b54eab38b11c8ba19a6">PCintPort::delPin</a></div><div class="ttdeci">void delPin(uint8_t mask)</div><div class="ttdef"><b>Definition:</b> PinChangeInt.cpp:51</div></div>
|
||||
</div><!-- fragment --></div><!-- contents -->
|
||||
<!-- start footer part -->
|
||||
<hr class="footer"/><address class="footer"><small>
|
||||
Generated by <a href="https://www.doxygen.org/index.html"><img class="footer" src="doxygen.svg" width="104" height="31" alt="doxygen"/></a> 1.9.1
|
||||
</small></address>
|
||||
</body>
|
||||
</html>
|
@ -1,790 +0,0 @@
|
||||
<!DOCTYPE html PUBLIC "-//W3C//DTD XHTML 1.0 Transitional//EN" "https://www.w3.org/TR/xhtml1/DTD/xhtml1-transitional.dtd">
|
||||
<html xmlns="http://www.w3.org/1999/xhtml">
|
||||
<head>
|
||||
<meta http-equiv="Content-Type" content="text/xhtml;charset=UTF-8"/>
|
||||
<meta http-equiv="X-UA-Compatible" content="IE=9"/>
|
||||
<meta name="generator" content="Doxygen 1.9.1"/>
|
||||
<meta name="viewport" content="width=device-width, initial-scale=1"/>
|
||||
<title>DCAITI Robot Hardware: src/communication/UARTCom.cpp File Reference</title>
|
||||
<link href="tabs.css" rel="stylesheet" type="text/css"/>
|
||||
<script type="text/javascript" src="jquery.js"></script>
|
||||
<script type="text/javascript" src="dynsections.js"></script>
|
||||
<link href="search/search.css" rel="stylesheet" type="text/css"/>
|
||||
<script type="text/javascript" src="search/searchdata.js"></script>
|
||||
<script type="text/javascript" src="search/search.js"></script>
|
||||
<link href="doxygen.css" rel="stylesheet" type="text/css" />
|
||||
</head>
|
||||
<body>
|
||||
<div id="top"><!-- do not remove this div, it is closed by doxygen! -->
|
||||
<div id="titlearea">
|
||||
<table cellspacing="0" cellpadding="0">
|
||||
<tbody>
|
||||
<tr style="height: 56px;">
|
||||
<td id="projectalign" style="padding-left: 0.5em;">
|
||||
<div id="projectname">DCAITI Robot Hardware
|
||||
 <span id="projectnumber">1.0</span>
|
||||
</div>
|
||||
</td>
|
||||
</tr>
|
||||
</tbody>
|
||||
</table>
|
||||
</div>
|
||||
<!-- end header part -->
|
||||
<!-- Generated by Doxygen 1.9.1 -->
|
||||
<script type="text/javascript">
|
||||
/* @license magnet:?xt=urn:btih:cf05388f2679ee054f2beb29a391d25f4e673ac3&dn=gpl-2.0.txt GPL-v2 */
|
||||
var searchBox = new SearchBox("searchBox", "search",false,'Search','.html');
|
||||
/* @license-end */
|
||||
</script>
|
||||
<script type="text/javascript" src="menudata.js"></script>
|
||||
<script type="text/javascript" src="menu.js"></script>
|
||||
<script type="text/javascript">
|
||||
/* @license magnet:?xt=urn:btih:cf05388f2679ee054f2beb29a391d25f4e673ac3&dn=gpl-2.0.txt GPL-v2 */
|
||||
$(function() {
|
||||
initMenu('',true,false,'search.php','Search');
|
||||
$(document).ready(function() { init_search(); });
|
||||
});
|
||||
/* @license-end */</script>
|
||||
<div id="main-nav"></div>
|
||||
<!-- window showing the filter options -->
|
||||
<div id="MSearchSelectWindow"
|
||||
onmouseover="return searchBox.OnSearchSelectShow()"
|
||||
onmouseout="return searchBox.OnSearchSelectHide()"
|
||||
onkeydown="return searchBox.OnSearchSelectKey(event)">
|
||||
</div>
|
||||
|
||||
<!-- iframe showing the search results (closed by default) -->
|
||||
<div id="MSearchResultsWindow">
|
||||
<iframe src="javascript:void(0)" frameborder="0"
|
||||
name="MSearchResults" id="MSearchResults">
|
||||
</iframe>
|
||||
</div>
|
||||
|
||||
<div id="nav-path" class="navpath">
|
||||
<ul>
|
||||
<li class="navelem"><a class="el" href="dir_68267d1309a1af8e8297ef4c3efbcdba.html">src</a></li><li class="navelem"><a class="el" href="dir_6d2104db64b91953bbd7b8fedbb8a094.html">communication</a></li> </ul>
|
||||
</div>
|
||||
</div><!-- top -->
|
||||
<div class="header">
|
||||
<div class="summary">
|
||||
<a href="#func-members">Functions</a> |
|
||||
<a href="#var-members">Variables</a> </div>
|
||||
<div class="headertitle">
|
||||
<div class="title">UARTCom.cpp File Reference</div> </div>
|
||||
</div><!--header-->
|
||||
<div class="contents">
|
||||
<div class="textblock"><code>#include "<a class="el" href="UARTCom_8hpp_source.html">communication/UARTCom.hpp</a>"</code><br />
|
||||
<code>#include "<a class="el" href="UCommands_8hpp_source.html">communication/UCommands.hpp</a>"</code><br />
|
||||
<code>#include "<a class="el" href="UValue_8hpp_source.html">communication/UValue.hpp</a>"</code><br />
|
||||
<code>#include "<a class="el" href="Utils_8hpp_source.html">misc/Utils.hpp</a>"</code><br />
|
||||
<code>#include "<a class="el" href="constants_8h_source.html">constants.h</a>"</code><br />
|
||||
<code>#include "MotorWheel.h"</code><br />
|
||||
</div><div class="textblock"><div class="dynheader">
|
||||
Include dependency graph for UARTCom.cpp:</div>
|
||||
<div class="dyncontent">
|
||||
<div class="center"><img src="UARTCom_8cpp__incl.png" border="0" usemap="#asrc_2communication_2UARTCom_8cpp" alt=""/></div>
|
||||
<map name="asrc_2communication_2UARTCom_8cpp" id="asrc_2communication_2UARTCom_8cpp">
|
||||
<area shape="rect" title=" " alt="" coords="465,5,708,32"/>
|
||||
<area shape="rect" href="UARTCom_8hpp.html" title="class to manage uart communication" alt="" coords="145,80,365,107"/>
|
||||
<area shape="rect" href="constants_8h.html" title=" " alt="" coords="538,155,635,181"/>
|
||||
<area shape="rect" href="UCommands_8hpp.html" title="implementation of commands according to uart protocol" alt="" coords="389,80,627,107"/>
|
||||
<area shape="rect" href="UValue_8hpp.html" title="class to send out encoder values" alt="" coords="703,80,905,107"/>
|
||||
<area shape="rect" href="Utils_8hpp.html" title="useful converting and computing functions" alt="" coords="5,80,120,107"/>
|
||||
<area shape="rect" title=" " alt="" coords="930,80,1043,107"/>
|
||||
<area shape="rect" title=" " alt="" coords="213,155,297,181"/>
|
||||
</map>
|
||||
</div>
|
||||
</div><table class="memberdecls">
|
||||
<tr class="heading"><td colspan="2"><h2 class="groupheader"><a name="func-members"></a>
|
||||
Functions</h2></td></tr>
|
||||
<tr class="memitem:a5bfcc9a4d05eaa07aff6dbc5ffbc01a4"><td class="memItemLeft" align="right" valign="top"><a class="el" href="constants_8h.html#a2cadd9c064904e21e2acd0d0f64ad8b6">U_FrameType</a> </td><td class="memItemRight" valign="bottom"><a class="el" href="UARTCom_8cpp.html#a5bfcc9a4d05eaa07aff6dbc5ffbc01a4">parseFrameType</a> (uint8_t *d)</td></tr>
|
||||
<tr class="memdesc:a5bfcc9a4d05eaa07aff6dbc5ffbc01a4"><td class="mdescLeft"> </td><td class="mdescRight">extracts frametype from data package <a href="UARTCom_8cpp.html#a5bfcc9a4d05eaa07aff6dbc5ffbc01a4">More...</a><br /></td></tr>
|
||||
<tr class="separator:a5bfcc9a4d05eaa07aff6dbc5ffbc01a4"><td class="memSeparator" colspan="2"> </td></tr>
|
||||
<tr class="memitem:a4d3197ea3a99346e142f898a856eba6c"><td class="memItemLeft" align="right" valign="top">uint8_t </td><td class="memItemRight" valign="bottom"><a class="el" href="UARTCom_8cpp.html#a4d3197ea3a99346e142f898a856eba6c">fromFrameType</a> (<a class="el" href="constants_8h.html#a2cadd9c064904e21e2acd0d0f64ad8b6">U_FrameType</a> ft)</td></tr>
|
||||
<tr class="memdesc:a4d3197ea3a99346e142f898a856eba6c"><td class="mdescLeft"> </td><td class="mdescRight">translates frametype to corresponding byte value <a href="UARTCom_8cpp.html#a4d3197ea3a99346e142f898a856eba6c">More...</a><br /></td></tr>
|
||||
<tr class="separator:a4d3197ea3a99346e142f898a856eba6c"><td class="memSeparator" colspan="2"> </td></tr>
|
||||
<tr class="memitem:a2f281c7608e509d555fc0a09cfeff82a"><td class="memItemLeft" align="right" valign="top"><a class="el" href="constants_8h.html#a35f6afe79ab48a3034b81cb15d538155">U_Component</a> </td><td class="memItemRight" valign="bottom"><a class="el" href="UARTCom_8cpp.html#a2f281c7608e509d555fc0a09cfeff82a">parseComponent</a> (uint8_t *d)</td></tr>
|
||||
<tr class="memdesc:a2f281c7608e509d555fc0a09cfeff82a"><td class="mdescLeft"> </td><td class="mdescRight">extract component information <a href="UARTCom_8cpp.html#a2f281c7608e509d555fc0a09cfeff82a">More...</a><br /></td></tr>
|
||||
<tr class="separator:a2f281c7608e509d555fc0a09cfeff82a"><td class="memSeparator" colspan="2"> </td></tr>
|
||||
<tr class="memitem:a050546b686b2c4648e34f5145e8e5c3a"><td class="memItemLeft" align="right" valign="top">uint8_t </td><td class="memItemRight" valign="bottom"><a class="el" href="UARTCom_8cpp.html#a050546b686b2c4648e34f5145e8e5c3a">fromComponent</a> (<a class="el" href="constants_8h.html#a35f6afe79ab48a3034b81cb15d538155">U_Component</a> cp)</td></tr>
|
||||
<tr class="memdesc:a050546b686b2c4648e34f5145e8e5c3a"><td class="mdescLeft"> </td><td class="mdescRight">translates component into byte value <a href="UARTCom_8cpp.html#a050546b686b2c4648e34f5145e8e5c3a">More...</a><br /></td></tr>
|
||||
<tr class="separator:a050546b686b2c4648e34f5145e8e5c3a"><td class="memSeparator" colspan="2"> </td></tr>
|
||||
<tr class="memitem:a67a111cec96745786304360702d7fb0d"><td class="memItemLeft" align="right" valign="top"><a class="el" href="constants_8h.html#a83703b84abb8c92901ec1c15e0bbad80">U_Request</a> </td><td class="memItemRight" valign="bottom"><a class="el" href="UARTCom_8cpp.html#a67a111cec96745786304360702d7fb0d">parseRequest</a> (uint8_t *d)</td></tr>
|
||||
<tr class="memdesc:a67a111cec96745786304360702d7fb0d"><td class="mdescLeft"> </td><td class="mdescRight">extracts request information from data package <a href="UARTCom_8cpp.html#a67a111cec96745786304360702d7fb0d">More...</a><br /></td></tr>
|
||||
<tr class="separator:a67a111cec96745786304360702d7fb0d"><td class="memSeparator" colspan="2"> </td></tr>
|
||||
<tr class="memitem:ac85d37d78756559b8b923544852dd430"><td class="memItemLeft" align="right" valign="top">uint32_t </td><td class="memItemRight" valign="bottom"><a class="el" href="UARTCom_8cpp.html#ac85d37d78756559b8b923544852dd430">parseTimestamp</a> (uint8_t *d)</td></tr>
|
||||
<tr class="memdesc:ac85d37d78756559b8b923544852dd430"><td class="mdescLeft"> </td><td class="mdescRight">extracts timestamp from data package <a href="UARTCom_8cpp.html#ac85d37d78756559b8b923544852dd430">More...</a><br /></td></tr>
|
||||
<tr class="separator:ac85d37d78756559b8b923544852dd430"><td class="memSeparator" colspan="2"> </td></tr>
|
||||
<tr class="memitem:a744c5a2f1e07b896f5dc1a3b352dfd2a"><td class="memItemLeft" align="right" valign="top">uint16_t </td><td class="memItemRight" valign="bottom"><a class="el" href="UARTCom_8cpp.html#a744c5a2f1e07b896f5dc1a3b352dfd2a">computeChecksum</a> (uint8_t *d, uint8_t pl)</td></tr>
|
||||
<tr class="memdesc:a744c5a2f1e07b896f5dc1a3b352dfd2a"><td class="mdescLeft"> </td><td class="mdescRight">computes checksum from data package <a href="UARTCom_8cpp.html#a744c5a2f1e07b896f5dc1a3b352dfd2a">More...</a><br /></td></tr>
|
||||
<tr class="separator:a744c5a2f1e07b896f5dc1a3b352dfd2a"><td class="memSeparator" colspan="2"> </td></tr>
|
||||
<tr class="memitem:a09ed133ea78335824acd3d296d6d8568"><td class="memItemLeft" align="right" valign="top">int </td><td class="memItemRight" valign="bottom"><a class="el" href="UARTCom_8cpp.html#a09ed133ea78335824acd3d296d6d8568">correctChecksum</a> (uint8_t *d)</td></tr>
|
||||
<tr class="memdesc:a09ed133ea78335824acd3d296d6d8568"><td class="mdescLeft"> </td><td class="mdescRight">checks if checksum inside package and computed checksum from package data are the same <a href="UARTCom_8cpp.html#a09ed133ea78335824acd3d296d6d8568">More...</a><br /></td></tr>
|
||||
<tr class="separator:a09ed133ea78335824acd3d296d6d8568"><td class="memSeparator" colspan="2"> </td></tr>
|
||||
<tr class="memitem:ac77fffc0c7f612ccf0db14af856e3277"><td class="memItemLeft" align="right" valign="top">void </td><td class="memItemRight" valign="bottom"><a class="el" href="UARTCom_8cpp.html#ac77fffc0c7f612ccf0db14af856e3277">showPackage</a> (uint8_t *d, int pl)</td></tr>
|
||||
<tr class="memdesc:ac77fffc0c7f612ccf0db14af856e3277"><td class="mdescLeft"> </td><td class="mdescRight">debugging function, prints out package data <a href="UARTCom_8cpp.html#ac77fffc0c7f612ccf0db14af856e3277">More...</a><br /></td></tr>
|
||||
<tr class="separator:ac77fffc0c7f612ccf0db14af856e3277"><td class="memSeparator" colspan="2"> </td></tr>
|
||||
<tr class="memitem:a0f9de5ab46a6f02e563fdc4634cd1b26"><td class="memItemLeft" align="right" valign="top">void </td><td class="memItemRight" valign="bottom"><a class="el" href="UARTCom_8cpp.html#a0f9de5ab46a6f02e563fdc4634cd1b26">clearPackage</a> (uint8_t *d)</td></tr>
|
||||
<tr class="memdesc:a0f9de5ab46a6f02e563fdc4634cd1b26"><td class="mdescLeft"> </td><td class="mdescRight">erases all package data and sets the array to 0 <a href="UARTCom_8cpp.html#a0f9de5ab46a6f02e563fdc4634cd1b26">More...</a><br /></td></tr>
|
||||
<tr class="separator:a0f9de5ab46a6f02e563fdc4634cd1b26"><td class="memSeparator" colspan="2"> </td></tr>
|
||||
<tr class="memitem:a8f3f9f5697687756152cfc8045170646"><td class="memItemLeft" align="right" valign="top">void </td><td class="memItemRight" valign="bottom"><a class="el" href="UARTCom_8cpp.html#a8f3f9f5697687756152cfc8045170646">handleRequest</a> (uint8_t *d)</td></tr>
|
||||
<tr class="memdesc:a8f3f9f5697687756152cfc8045170646"><td class="mdescLeft"> </td><td class="mdescRight">executes commands according to incoming request <a href="UARTCom_8cpp.html#a8f3f9f5697687756152cfc8045170646">More...</a><br /></td></tr>
|
||||
<tr class="separator:a8f3f9f5697687756152cfc8045170646"><td class="memSeparator" colspan="2"> </td></tr>
|
||||
<tr class="memitem:a86f7112e2f3c0cf6e89e6cc9ce0d35bc"><td class="memItemLeft" align="right" valign="top">void </td><td class="memItemRight" valign="bottom"><a class="el" href="UARTCom_8cpp.html#a86f7112e2f3c0cf6e89e6cc9ce0d35bc">handlePackage</a> (uint8_t *d, int pl)</td></tr>
|
||||
<tr class="memdesc:a86f7112e2f3c0cf6e89e6cc9ce0d35bc"><td class="mdescLeft"> </td><td class="mdescRight">package handler, checks for errors first, then proceeds to extract information from the data package <a href="UARTCom_8cpp.html#a86f7112e2f3c0cf6e89e6cc9ce0d35bc">More...</a><br /></td></tr>
|
||||
<tr class="separator:a86f7112e2f3c0cf6e89e6cc9ce0d35bc"><td class="memSeparator" colspan="2"> </td></tr>
|
||||
</table><table class="memberdecls">
|
||||
<tr class="heading"><td colspan="2"><h2 class="groupheader"><a name="var-members"></a>
|
||||
Variables</h2></td></tr>
|
||||
<tr class="memitem:aa786999c8aa65490b5b03fb09a9f1f98"><td class="memItemLeft" align="right" valign="top">uint8_t </td><td class="memItemRight" valign="bottom"><a class="el" href="UARTCom_8cpp.html#aa786999c8aa65490b5b03fb09a9f1f98">currentParseIndex</a></td></tr>
|
||||
<tr class="separator:aa786999c8aa65490b5b03fb09a9f1f98"><td class="memSeparator" colspan="2"> </td></tr>
|
||||
<tr class="memitem:a2eead10869c5f921ef036aa656683cd5"><td class="memItemLeft" align="right" valign="top">int </td><td class="memItemRight" valign="bottom"><a class="el" href="UARTCom_8cpp.html#a2eead10869c5f921ef036aa656683cd5">payloadLength</a></td></tr>
|
||||
<tr class="separator:a2eead10869c5f921ef036aa656683cd5"><td class="memSeparator" colspan="2"> </td></tr>
|
||||
<tr class="memitem:aae4c1b8c8e6cca37d95276b38497b370"><td class="memItemLeft" align="right" valign="top">uint32_t </td><td class="memItemRight" valign="bottom"><a class="el" href="UARTCom_8cpp.html#aae4c1b8c8e6cca37d95276b38497b370">currentTimestamp</a> = 0</td></tr>
|
||||
<tr class="separator:aae4c1b8c8e6cca37d95276b38497b370"><td class="memSeparator" colspan="2"> </td></tr>
|
||||
<tr class="memitem:adeaeefb426fbd7c5a72fffec28ee0c46"><td class="memItemLeft" align="right" valign="top">MotorWheel </td><td class="memItemRight" valign="bottom"><a class="el" href="UARTCom_8cpp.html#adeaeefb426fbd7c5a72fffec28ee0c46">wheelLeft</a></td></tr>
|
||||
<tr class="separator:adeaeefb426fbd7c5a72fffec28ee0c46"><td class="memSeparator" colspan="2"> </td></tr>
|
||||
<tr class="memitem:a5ab69515b5724f039c137585cbf24787"><td class="memItemLeft" align="right" valign="top">MotorWheel </td><td class="memItemRight" valign="bottom"><a class="el" href="UARTCom_8cpp.html#a5ab69515b5724f039c137585cbf24787">wheelRight</a></td></tr>
|
||||
<tr class="separator:a5ab69515b5724f039c137585cbf24787"><td class="memSeparator" colspan="2"> </td></tr>
|
||||
</table>
|
||||
<h2 class="groupheader">Function Documentation</h2>
|
||||
<a id="a0f9de5ab46a6f02e563fdc4634cd1b26"></a>
|
||||
<h2 class="memtitle"><span class="permalink"><a href="#a0f9de5ab46a6f02e563fdc4634cd1b26">◆ </a></span>clearPackage()</h2>
|
||||
|
||||
<div class="memitem">
|
||||
<div class="memproto">
|
||||
<table class="memname">
|
||||
<tr>
|
||||
<td class="memname">void clearPackage </td>
|
||||
<td>(</td>
|
||||
<td class="paramtype">uint8_t * </td>
|
||||
<td class="paramname"><em>d</em></td><td>)</td>
|
||||
<td></td>
|
||||
</tr>
|
||||
</table>
|
||||
</div><div class="memdoc">
|
||||
|
||||
<p>erases all package data and sets the array to 0 </p>
|
||||
<dl class="params"><dt>Parameters</dt><dd>
|
||||
<table class="params">
|
||||
<tr><td class="paramname">d</td><td>data package </td></tr>
|
||||
</table>
|
||||
</dd>
|
||||
</dl>
|
||||
<div class="dynheader">
|
||||
Here is the caller graph for this function:</div>
|
||||
<div class="dyncontent">
|
||||
<div class="center"><img src="UARTCom_8cpp_a0f9de5ab46a6f02e563fdc4634cd1b26_icgraph.png" border="0" usemap="#aUARTCom_8cpp_a0f9de5ab46a6f02e563fdc4634cd1b26_icgraph" alt=""/></div>
|
||||
<map name="aUARTCom_8cpp_a0f9de5ab46a6f02e563fdc4634cd1b26_icgraph" id="aUARTCom_8cpp_a0f9de5ab46a6f02e563fdc4634cd1b26_icgraph">
|
||||
<area shape="rect" title="erases all package data and sets the array to 0" alt="" coords="284,31,393,57"/>
|
||||
<area shape="rect" href="classUARTCom.html#a0b8f43f58c7ed25f191a0339ad0f170d" title="initializes uart communication" alt="" coords="116,5,232,32"/>
|
||||
<area shape="rect" href="classUARTCom.html#a38e053e8c8bcad7735c7fe09bfc84ffd" title="reads uart interface and stores the data into an uint8_t array" alt="" coords="112,56,236,83"/>
|
||||
<area shape="rect" href="main_8cpp.html#a7dfd9b79bc5a37d7df40207afbc5431f" title=" " alt="" coords="5,5,64,32"/>
|
||||
<area shape="rect" href="main_8cpp.html#a0b33edabd7f1c4e4a0bf32c67269be2f" title=" " alt="" coords="9,56,60,83"/>
|
||||
</map>
|
||||
</div>
|
||||
|
||||
</div>
|
||||
</div>
|
||||
<a id="a744c5a2f1e07b896f5dc1a3b352dfd2a"></a>
|
||||
<h2 class="memtitle"><span class="permalink"><a href="#a744c5a2f1e07b896f5dc1a3b352dfd2a">◆ </a></span>computeChecksum()</h2>
|
||||
|
||||
<div class="memitem">
|
||||
<div class="memproto">
|
||||
<table class="memname">
|
||||
<tr>
|
||||
<td class="memname">uint16_t computeChecksum </td>
|
||||
<td>(</td>
|
||||
<td class="paramtype">uint8_t * </td>
|
||||
<td class="paramname"><em>d</em>, </td>
|
||||
</tr>
|
||||
<tr>
|
||||
<td class="paramkey"></td>
|
||||
<td></td>
|
||||
<td class="paramtype">uint8_t </td>
|
||||
<td class="paramname"><em>pl</em> </td>
|
||||
</tr>
|
||||
<tr>
|
||||
<td></td>
|
||||
<td>)</td>
|
||||
<td></td><td></td>
|
||||
</tr>
|
||||
</table>
|
||||
</div><div class="memdoc">
|
||||
|
||||
<p>computes checksum from data package </p>
|
||||
<dl class="params"><dt>Parameters</dt><dd>
|
||||
<table class="params">
|
||||
<tr><td class="paramname">d</td><td>data package </td></tr>
|
||||
<tr><td class="paramname">pl</td><td>payload length </td></tr>
|
||||
</table>
|
||||
</dd>
|
||||
</dl>
|
||||
<dl class="section return"><dt>Returns</dt><dd>uint16_t </dd></dl>
|
||||
<div class="dynheader">
|
||||
Here is the caller graph for this function:</div>
|
||||
<div class="dyncontent">
|
||||
<div class="center"><img src="UARTCom_8cpp_a744c5a2f1e07b896f5dc1a3b352dfd2a_icgraph.png" border="0" usemap="#aUARTCom_8cpp_a744c5a2f1e07b896f5dc1a3b352dfd2a_icgraph" alt=""/></div>
|
||||
<map name="aUARTCom_8cpp_a744c5a2f1e07b896f5dc1a3b352dfd2a_icgraph" id="aUARTCom_8cpp_a744c5a2f1e07b896f5dc1a3b352dfd2a_icgraph">
|
||||
<area shape="rect" title="computes checksum from data package" alt="" coords="628,5,775,32"/>
|
||||
<area shape="rect" href="UARTCom_8cpp.html#a09ed133ea78335824acd3d296d6d8568" title="checks if checksum inside package and computed checksum from package data are the same" alt="" coords="445,5,580,32"/>
|
||||
<area shape="rect" href="UARTCom_8cpp.html#a86f7112e2f3c0cf6e89e6cc9ce0d35bc" title="package handler, checks for errors first, then proceeds to extract information from the data package" alt="" coords="276,5,397,32"/>
|
||||
<area shape="rect" href="classUARTCom.html#a38e053e8c8bcad7735c7fe09bfc84ffd" title="reads uart interface and stores the data into an uint8_t array" alt="" coords="104,5,228,32"/>
|
||||
<area shape="rect" href="main_8cpp.html#a0b33edabd7f1c4e4a0bf32c67269be2f" title=" " alt="" coords="5,5,56,32"/>
|
||||
</map>
|
||||
</div>
|
||||
|
||||
</div>
|
||||
</div>
|
||||
<a id="a09ed133ea78335824acd3d296d6d8568"></a>
|
||||
<h2 class="memtitle"><span class="permalink"><a href="#a09ed133ea78335824acd3d296d6d8568">◆ </a></span>correctChecksum()</h2>
|
||||
|
||||
<div class="memitem">
|
||||
<div class="memproto">
|
||||
<table class="memname">
|
||||
<tr>
|
||||
<td class="memname">int correctChecksum </td>
|
||||
<td>(</td>
|
||||
<td class="paramtype">uint8_t * </td>
|
||||
<td class="paramname"><em>d</em></td><td>)</td>
|
||||
<td></td>
|
||||
</tr>
|
||||
</table>
|
||||
</div><div class="memdoc">
|
||||
|
||||
<p>checks if checksum inside package and computed checksum from package data are the same </p>
|
||||
<dl class="params"><dt>Parameters</dt><dd>
|
||||
<table class="params">
|
||||
<tr><td class="paramname">d</td><td>data package </td></tr>
|
||||
</table>
|
||||
</dd>
|
||||
</dl>
|
||||
<dl class="section return"><dt>Returns</dt><dd>int </dd></dl>
|
||||
<div class="dynheader">
|
||||
Here is the call graph for this function:</div>
|
||||
<div class="dyncontent">
|
||||
<div class="center"><img src="UARTCom_8cpp_a09ed133ea78335824acd3d296d6d8568_cgraph.png" border="0" usemap="#aUARTCom_8cpp_a09ed133ea78335824acd3d296d6d8568_cgraph" alt=""/></div>
|
||||
<map name="aUARTCom_8cpp_a09ed133ea78335824acd3d296d6d8568_cgraph" id="aUARTCom_8cpp_a09ed133ea78335824acd3d296d6d8568_cgraph">
|
||||
<area shape="rect" title="checks if checksum inside package and computed checksum from package data are the same" alt="" coords="5,5,140,32"/>
|
||||
<area shape="rect" href="UARTCom_8cpp.html#a744c5a2f1e07b896f5dc1a3b352dfd2a" title="computes checksum from data package" alt="" coords="188,5,335,32"/>
|
||||
</map>
|
||||
</div>
|
||||
<div class="dynheader">
|
||||
Here is the caller graph for this function:</div>
|
||||
<div class="dyncontent">
|
||||
<div class="center"><img src="UARTCom_8cpp_a09ed133ea78335824acd3d296d6d8568_icgraph.png" border="0" usemap="#aUARTCom_8cpp_a09ed133ea78335824acd3d296d6d8568_icgraph" alt=""/></div>
|
||||
<map name="aUARTCom_8cpp_a09ed133ea78335824acd3d296d6d8568_icgraph" id="aUARTCom_8cpp_a09ed133ea78335824acd3d296d6d8568_icgraph">
|
||||
<area shape="rect" title="checks if checksum inside package and computed checksum from package data are the same" alt="" coords="445,5,580,32"/>
|
||||
<area shape="rect" href="UARTCom_8cpp.html#a86f7112e2f3c0cf6e89e6cc9ce0d35bc" title="package handler, checks for errors first, then proceeds to extract information from the data package" alt="" coords="276,5,397,32"/>
|
||||
<area shape="rect" href="classUARTCom.html#a38e053e8c8bcad7735c7fe09bfc84ffd" title="reads uart interface and stores the data into an uint8_t array" alt="" coords="104,5,228,32"/>
|
||||
<area shape="rect" href="main_8cpp.html#a0b33edabd7f1c4e4a0bf32c67269be2f" title=" " alt="" coords="5,5,56,32"/>
|
||||
</map>
|
||||
</div>
|
||||
|
||||
</div>
|
||||
</div>
|
||||
<a id="a050546b686b2c4648e34f5145e8e5c3a"></a>
|
||||
<h2 class="memtitle"><span class="permalink"><a href="#a050546b686b2c4648e34f5145e8e5c3a">◆ </a></span>fromComponent()</h2>
|
||||
|
||||
<div class="memitem">
|
||||
<div class="memproto">
|
||||
<table class="memname">
|
||||
<tr>
|
||||
<td class="memname">uint8_t fromComponent </td>
|
||||
<td>(</td>
|
||||
<td class="paramtype"><a class="el" href="constants_8h.html#a35f6afe79ab48a3034b81cb15d538155">U_Component</a> </td>
|
||||
<td class="paramname"><em>cp</em></td><td>)</td>
|
||||
<td></td>
|
||||
</tr>
|
||||
</table>
|
||||
</div><div class="memdoc">
|
||||
|
||||
<p>translates component into byte value </p>
|
||||
<dl class="params"><dt>Parameters</dt><dd>
|
||||
<table class="params">
|
||||
<tr><td class="paramname">cp</td><td>component </td></tr>
|
||||
</table>
|
||||
</dd>
|
||||
</dl>
|
||||
<dl class="section return"><dt>Returns</dt><dd>uint8_t </dd></dl>
|
||||
<div class="dynheader">
|
||||
Here is the caller graph for this function:</div>
|
||||
<div class="dyncontent">
|
||||
<div class="center"><img src="UARTCom_8cpp_a050546b686b2c4648e34f5145e8e5c3a_icgraph.png" border="0" usemap="#aUARTCom_8cpp_a050546b686b2c4648e34f5145e8e5c3a_icgraph" alt=""/></div>
|
||||
<map name="aUARTCom_8cpp_a050546b686b2c4648e34f5145e8e5c3a_icgraph" id="aUARTCom_8cpp_a050546b686b2c4648e34f5145e8e5c3a_icgraph">
|
||||
<area shape="rect" title="translates component into byte value" alt="" coords="1069,56,1197,83"/>
|
||||
<area shape="rect" href="classUARTCom.html#a7d317999b89947edc57ba32012c9522f" title="assembles and sends a uart package" alt="" coords="895,56,1021,83"/>
|
||||
<area shape="rect" href="classUValue.html#a92218410a1f6b266c142fe4f2af704ae" title="send both encoder values via uart" alt="" coords="612,5,847,32"/>
|
||||
<area shape="rect" href="classUValue.html#ac1818040e6bca1803b368b958db7333b" title="sends encoder value via uart" alt="" coords="631,56,828,83"/>
|
||||
<area shape="rect" href="main_8cpp.html#a7dfd9b79bc5a37d7df40207afbc5431f" title=" " alt="" coords="700,107,759,133"/>
|
||||
<area shape="rect" href="UARTCom_8cpp.html#a8f3f9f5697687756152cfc8045170646" title="executes commands according to incoming request" alt="" coords="445,5,564,32"/>
|
||||
<area shape="rect" href="UARTCom_8cpp.html#a86f7112e2f3c0cf6e89e6cc9ce0d35bc" title="package handler, checks for errors first, then proceeds to extract information from the data package" alt="" coords="276,5,397,32"/>
|
||||
<area shape="rect" href="classUARTCom.html#a38e053e8c8bcad7735c7fe09bfc84ffd" title="reads uart interface and stores the data into an uint8_t array" alt="" coords="104,5,228,32"/>
|
||||
<area shape="rect" href="main_8cpp.html#a0b33edabd7f1c4e4a0bf32c67269be2f" title=" " alt="" coords="5,5,56,32"/>
|
||||
</map>
|
||||
</div>
|
||||
|
||||
</div>
|
||||
</div>
|
||||
<a id="a4d3197ea3a99346e142f898a856eba6c"></a>
|
||||
<h2 class="memtitle"><span class="permalink"><a href="#a4d3197ea3a99346e142f898a856eba6c">◆ </a></span>fromFrameType()</h2>
|
||||
|
||||
<div class="memitem">
|
||||
<div class="memproto">
|
||||
<table class="memname">
|
||||
<tr>
|
||||
<td class="memname">uint8_t fromFrameType </td>
|
||||
<td>(</td>
|
||||
<td class="paramtype"><a class="el" href="constants_8h.html#a2cadd9c064904e21e2acd0d0f64ad8b6">U_FrameType</a> </td>
|
||||
<td class="paramname"><em>ft</em></td><td>)</td>
|
||||
<td></td>
|
||||
</tr>
|
||||
</table>
|
||||
</div><div class="memdoc">
|
||||
|
||||
<p>translates frametype to corresponding byte value </p>
|
||||
<dl class="params"><dt>Parameters</dt><dd>
|
||||
<table class="params">
|
||||
<tr><td class="paramname">ft</td><td>frametype </td></tr>
|
||||
</table>
|
||||
</dd>
|
||||
</dl>
|
||||
<dl class="section return"><dt>Returns</dt><dd>uint8_t </dd></dl>
|
||||
<div class="dynheader">
|
||||
Here is the caller graph for this function:</div>
|
||||
<div class="dyncontent">
|
||||
<div class="center"><img src="UARTCom_8cpp_a4d3197ea3a99346e142f898a856eba6c_icgraph.png" border="0" usemap="#aUARTCom_8cpp_a4d3197ea3a99346e142f898a856eba6c_icgraph" alt=""/></div>
|
||||
<map name="aUARTCom_8cpp_a4d3197ea3a99346e142f898a856eba6c_icgraph" id="aUARTCom_8cpp_a4d3197ea3a99346e142f898a856eba6c_icgraph">
|
||||
<area shape="rect" title="translates frametype to corresponding byte value" alt="" coords="1069,56,1193,83"/>
|
||||
<area shape="rect" href="classUARTCom.html#a7d317999b89947edc57ba32012c9522f" title="assembles and sends a uart package" alt="" coords="895,56,1021,83"/>
|
||||
<area shape="rect" href="classUValue.html#a92218410a1f6b266c142fe4f2af704ae" title="send both encoder values via uart" alt="" coords="612,5,847,32"/>
|
||||
<area shape="rect" href="classUValue.html#ac1818040e6bca1803b368b958db7333b" title="sends encoder value via uart" alt="" coords="631,56,828,83"/>
|
||||
<area shape="rect" href="main_8cpp.html#a7dfd9b79bc5a37d7df40207afbc5431f" title=" " alt="" coords="700,107,759,133"/>
|
||||
<area shape="rect" href="UARTCom_8cpp.html#a8f3f9f5697687756152cfc8045170646" title="executes commands according to incoming request" alt="" coords="445,5,564,32"/>
|
||||
<area shape="rect" href="UARTCom_8cpp.html#a86f7112e2f3c0cf6e89e6cc9ce0d35bc" title="package handler, checks for errors first, then proceeds to extract information from the data package" alt="" coords="276,5,397,32"/>
|
||||
<area shape="rect" href="classUARTCom.html#a38e053e8c8bcad7735c7fe09bfc84ffd" title="reads uart interface and stores the data into an uint8_t array" alt="" coords="104,5,228,32"/>
|
||||
<area shape="rect" href="main_8cpp.html#a0b33edabd7f1c4e4a0bf32c67269be2f" title=" " alt="" coords="5,5,56,32"/>
|
||||
</map>
|
||||
</div>
|
||||
|
||||
</div>
|
||||
</div>
|
||||
<a id="a86f7112e2f3c0cf6e89e6cc9ce0d35bc"></a>
|
||||
<h2 class="memtitle"><span class="permalink"><a href="#a86f7112e2f3c0cf6e89e6cc9ce0d35bc">◆ </a></span>handlePackage()</h2>
|
||||
|
||||
<div class="memitem">
|
||||
<div class="memproto">
|
||||
<table class="memname">
|
||||
<tr>
|
||||
<td class="memname">void handlePackage </td>
|
||||
<td>(</td>
|
||||
<td class="paramtype">uint8_t * </td>
|
||||
<td class="paramname"><em>d</em>, </td>
|
||||
</tr>
|
||||
<tr>
|
||||
<td class="paramkey"></td>
|
||||
<td></td>
|
||||
<td class="paramtype">int </td>
|
||||
<td class="paramname"><em>pl</em> </td>
|
||||
</tr>
|
||||
<tr>
|
||||
<td></td>
|
||||
<td>)</td>
|
||||
<td></td><td></td>
|
||||
</tr>
|
||||
</table>
|
||||
</div><div class="memdoc">
|
||||
|
||||
<p>package handler, checks for errors first, then proceeds to extract information from the data package </p>
|
||||
<dl class="params"><dt>Parameters</dt><dd>
|
||||
<table class="params">
|
||||
<tr><td class="paramname">d</td><td></td></tr>
|
||||
<tr><td class="paramname">pl</td><td></td></tr>
|
||||
</table>
|
||||
</dd>
|
||||
</dl>
|
||||
<div class="dynheader">
|
||||
Here is the call graph for this function:</div>
|
||||
<div class="dyncontent">
|
||||
<div class="center"><img src="UARTCom_8cpp_a86f7112e2f3c0cf6e89e6cc9ce0d35bc_cgraph.png" border="0" usemap="#aUARTCom_8cpp_a86f7112e2f3c0cf6e89e6cc9ce0d35bc_cgraph" alt=""/></div>
|
||||
<map name="aUARTCom_8cpp_a86f7112e2f3c0cf6e89e6cc9ce0d35bc_cgraph" id="aUARTCom_8cpp_a86f7112e2f3c0cf6e89e6cc9ce0d35bc_cgraph">
|
||||
<area shape="rect" title="package handler, checks for errors first, then proceeds to extract information from the data package" alt="" coords="5,157,127,184"/>
|
||||
<area shape="rect" href="UARTCom_8cpp.html#a09ed133ea78335824acd3d296d6d8568" title="checks if checksum inside package and computed checksum from package data are the same" alt="" coords="175,44,309,71"/>
|
||||
<area shape="rect" href="UARTCom_8cpp.html#a8f3f9f5697687756152cfc8045170646" title="executes commands according to incoming request" alt="" coords="183,132,301,159"/>
|
||||
<area shape="rect" href="UARTCom_8cpp.html#a5bfcc9a4d05eaa07aff6dbc5ffbc01a4" title="extracts frametype from data package" alt="" coords="177,183,307,209"/>
|
||||
<area shape="rect" href="UARTCom_8cpp.html#ac77fffc0c7f612ccf0db14af856e3277" title="debugging function, prints out package data" alt="" coords="187,233,297,260"/>
|
||||
<area shape="rect" href="UARTCom_8cpp.html#a744c5a2f1e07b896f5dc1a3b352dfd2a" title="computes checksum from data package" alt="" coords="401,5,548,32"/>
|
||||
<area shape="rect" href="UARTCom_8cpp.html#a2f281c7608e509d555fc0a09cfeff82a" title="extract component information" alt="" coords="408,56,541,83"/>
|
||||
<area shape="rect" href="UARTCom_8cpp.html#a67a111cec96745786304360702d7fb0d" title="extracts request information from data package" alt="" coords="419,107,530,133"/>
|
||||
<area shape="rect" href="classUValue.html#a92218410a1f6b266c142fe4f2af704ae" title="send both encoder values via uart" alt="" coords="357,157,592,184"/>
|
||||
<area shape="rect" href="classUCommands.html#a86ec0e5a25fbf90d6588055a7ba1f312" title="sets the PID parameters" alt="" coords="363,259,587,285"/>
|
||||
<area shape="rect" href="classUCommands.html#a3c5115bbcd456140f899e978b38a2cb5" title="sets the desired velocity of a motor" alt="" coords="381,208,569,235"/>
|
||||
<area shape="rect" href="classUARTCom.html#a7d317999b89947edc57ba32012c9522f" title="assembles and sends a uart package" alt="" coords="648,157,775,184"/>
|
||||
<area shape="rect" href="UARTCom_8cpp.html#a050546b686b2c4648e34f5145e8e5c3a" title="translates component into byte value" alt="" coords="831,132,959,159"/>
|
||||
<area shape="rect" href="UARTCom_8cpp.html#a4d3197ea3a99346e142f898a856eba6c" title="translates frametype to corresponding byte value" alt="" coords="833,183,957,209"/>
|
||||
<area shape="rect" href="classUtils.html#aac3729a54c2dbd0461f5faa130429280" title="converts 4 bytes to float (big endian)" alt="" coords="640,208,783,235"/>
|
||||
<area shape="rect" href="classUtils.html#a994ae9cd902090355b4777f0dd28e95c" title="converts 4 bytes to uint32_t (big endian)" alt="" coords="648,259,775,285"/>
|
||||
</map>
|
||||
</div>
|
||||
<div class="dynheader">
|
||||
Here is the caller graph for this function:</div>
|
||||
<div class="dyncontent">
|
||||
<div class="center"><img src="UARTCom_8cpp_a86f7112e2f3c0cf6e89e6cc9ce0d35bc_icgraph.png" border="0" usemap="#aUARTCom_8cpp_a86f7112e2f3c0cf6e89e6cc9ce0d35bc_icgraph" alt=""/></div>
|
||||
<map name="aUARTCom_8cpp_a86f7112e2f3c0cf6e89e6cc9ce0d35bc_icgraph" id="aUARTCom_8cpp_a86f7112e2f3c0cf6e89e6cc9ce0d35bc_icgraph">
|
||||
<area shape="rect" title="package handler, checks for errors first, then proceeds to extract information from the data package" alt="" coords="276,5,397,32"/>
|
||||
<area shape="rect" href="classUARTCom.html#a38e053e8c8bcad7735c7fe09bfc84ffd" title="reads uart interface and stores the data into an uint8_t array" alt="" coords="104,5,228,32"/>
|
||||
<area shape="rect" href="main_8cpp.html#a0b33edabd7f1c4e4a0bf32c67269be2f" title=" " alt="" coords="5,5,56,32"/>
|
||||
</map>
|
||||
</div>
|
||||
|
||||
</div>
|
||||
</div>
|
||||
<a id="a8f3f9f5697687756152cfc8045170646"></a>
|
||||
<h2 class="memtitle"><span class="permalink"><a href="#a8f3f9f5697687756152cfc8045170646">◆ </a></span>handleRequest()</h2>
|
||||
|
||||
<div class="memitem">
|
||||
<div class="memproto">
|
||||
<table class="memname">
|
||||
<tr>
|
||||
<td class="memname">void handleRequest </td>
|
||||
<td>(</td>
|
||||
<td class="paramtype">uint8_t * </td>
|
||||
<td class="paramname"><em>d</em></td><td>)</td>
|
||||
<td></td>
|
||||
</tr>
|
||||
</table>
|
||||
</div><div class="memdoc">
|
||||
|
||||
<p>executes commands according to incoming request </p>
|
||||
<dl class="params"><dt>Parameters</dt><dd>
|
||||
<table class="params">
|
||||
<tr><td class="paramname">d</td><td>data package </td></tr>
|
||||
</table>
|
||||
</dd>
|
||||
</dl>
|
||||
<div class="dynheader">
|
||||
Here is the call graph for this function:</div>
|
||||
<div class="dyncontent">
|
||||
<div class="center"><img src="UARTCom_8cpp_a8f3f9f5697687756152cfc8045170646_cgraph.png" border="0" usemap="#aUARTCom_8cpp_a8f3f9f5697687756152cfc8045170646_cgraph" alt=""/></div>
|
||||
<map name="aUARTCom_8cpp_a8f3f9f5697687756152cfc8045170646_cgraph" id="aUARTCom_8cpp_a8f3f9f5697687756152cfc8045170646_cgraph">
|
||||
<area shape="rect" title="executes commands according to incoming request" alt="" coords="5,107,124,133"/>
|
||||
<area shape="rect" href="UARTCom_8cpp.html#a2f281c7608e509d555fc0a09cfeff82a" title="extract component information" alt="" coords="223,5,356,32"/>
|
||||
<area shape="rect" href="UARTCom_8cpp.html#a67a111cec96745786304360702d7fb0d" title="extracts request information from data package" alt="" coords="234,56,345,83"/>
|
||||
<area shape="rect" href="classUValue.html#a92218410a1f6b266c142fe4f2af704ae" title="send both encoder values via uart" alt="" coords="172,107,407,133"/>
|
||||
<area shape="rect" href="classUCommands.html#a86ec0e5a25fbf90d6588055a7ba1f312" title="sets the PID parameters" alt="" coords="177,208,401,235"/>
|
||||
<area shape="rect" href="classUCommands.html#a3c5115bbcd456140f899e978b38a2cb5" title="sets the desired velocity of a motor" alt="" coords="195,157,383,184"/>
|
||||
<area shape="rect" href="classUARTCom.html#a7d317999b89947edc57ba32012c9522f" title="assembles and sends a uart package" alt="" coords="463,107,589,133"/>
|
||||
<area shape="rect" href="UARTCom_8cpp.html#a050546b686b2c4648e34f5145e8e5c3a" title="translates component into byte value" alt="" coords="645,81,773,108"/>
|
||||
<area shape="rect" href="UARTCom_8cpp.html#a4d3197ea3a99346e142f898a856eba6c" title="translates frametype to corresponding byte value" alt="" coords="647,132,771,159"/>
|
||||
<area shape="rect" href="classUtils.html#aac3729a54c2dbd0461f5faa130429280" title="converts 4 bytes to float (big endian)" alt="" coords="455,157,597,184"/>
|
||||
<area shape="rect" href="classUtils.html#a994ae9cd902090355b4777f0dd28e95c" title="converts 4 bytes to uint32_t (big endian)" alt="" coords="463,208,589,235"/>
|
||||
</map>
|
||||
</div>
|
||||
<div class="dynheader">
|
||||
Here is the caller graph for this function:</div>
|
||||
<div class="dyncontent">
|
||||
<div class="center"><img src="UARTCom_8cpp_a8f3f9f5697687756152cfc8045170646_icgraph.png" border="0" usemap="#aUARTCom_8cpp_a8f3f9f5697687756152cfc8045170646_icgraph" alt=""/></div>
|
||||
<map name="aUARTCom_8cpp_a8f3f9f5697687756152cfc8045170646_icgraph" id="aUARTCom_8cpp_a8f3f9f5697687756152cfc8045170646_icgraph">
|
||||
<area shape="rect" title="executes commands according to incoming request" alt="" coords="445,5,564,32"/>
|
||||
<area shape="rect" href="UARTCom_8cpp.html#a86f7112e2f3c0cf6e89e6cc9ce0d35bc" title="package handler, checks for errors first, then proceeds to extract information from the data package" alt="" coords="276,5,397,32"/>
|
||||
<area shape="rect" href="classUARTCom.html#a38e053e8c8bcad7735c7fe09bfc84ffd" title="reads uart interface and stores the data into an uint8_t array" alt="" coords="104,5,228,32"/>
|
||||
<area shape="rect" href="main_8cpp.html#a0b33edabd7f1c4e4a0bf32c67269be2f" title=" " alt="" coords="5,5,56,32"/>
|
||||
</map>
|
||||
</div>
|
||||
|
||||
</div>
|
||||
</div>
|
||||
<a id="a2f281c7608e509d555fc0a09cfeff82a"></a>
|
||||
<h2 class="memtitle"><span class="permalink"><a href="#a2f281c7608e509d555fc0a09cfeff82a">◆ </a></span>parseComponent()</h2>
|
||||
|
||||
<div class="memitem">
|
||||
<div class="memproto">
|
||||
<table class="memname">
|
||||
<tr>
|
||||
<td class="memname"><a class="el" href="constants_8h.html#a35f6afe79ab48a3034b81cb15d538155">U_Component</a> parseComponent </td>
|
||||
<td>(</td>
|
||||
<td class="paramtype">uint8_t * </td>
|
||||
<td class="paramname"><em>d</em></td><td>)</td>
|
||||
<td></td>
|
||||
</tr>
|
||||
</table>
|
||||
</div><div class="memdoc">
|
||||
|
||||
<p>extract component information </p>
|
||||
<dl class="params"><dt>Parameters</dt><dd>
|
||||
<table class="params">
|
||||
<tr><td class="paramname">d</td><td>data package </td></tr>
|
||||
</table>
|
||||
</dd>
|
||||
</dl>
|
||||
<dl class="section return"><dt>Returns</dt><dd>U_Component </dd></dl>
|
||||
<div class="dynheader">
|
||||
Here is the caller graph for this function:</div>
|
||||
<div class="dyncontent">
|
||||
<div class="center"><img src="UARTCom_8cpp_a2f281c7608e509d555fc0a09cfeff82a_icgraph.png" border="0" usemap="#aUARTCom_8cpp_a2f281c7608e509d555fc0a09cfeff82a_icgraph" alt=""/></div>
|
||||
<map name="aUARTCom_8cpp_a2f281c7608e509d555fc0a09cfeff82a_icgraph" id="aUARTCom_8cpp_a2f281c7608e509d555fc0a09cfeff82a_icgraph">
|
||||
<area shape="rect" title="extract component information" alt="" coords="612,5,745,32"/>
|
||||
<area shape="rect" href="UARTCom_8cpp.html#a8f3f9f5697687756152cfc8045170646" title="executes commands according to incoming request" alt="" coords="445,5,564,32"/>
|
||||
<area shape="rect" href="UARTCom_8cpp.html#a86f7112e2f3c0cf6e89e6cc9ce0d35bc" title="package handler, checks for errors first, then proceeds to extract information from the data package" alt="" coords="276,5,397,32"/>
|
||||
<area shape="rect" href="classUARTCom.html#a38e053e8c8bcad7735c7fe09bfc84ffd" title="reads uart interface and stores the data into an uint8_t array" alt="" coords="104,5,228,32"/>
|
||||
<area shape="rect" href="main_8cpp.html#a0b33edabd7f1c4e4a0bf32c67269be2f" title=" " alt="" coords="5,5,56,32"/>
|
||||
</map>
|
||||
</div>
|
||||
|
||||
</div>
|
||||
</div>
|
||||
<a id="a5bfcc9a4d05eaa07aff6dbc5ffbc01a4"></a>
|
||||
<h2 class="memtitle"><span class="permalink"><a href="#a5bfcc9a4d05eaa07aff6dbc5ffbc01a4">◆ </a></span>parseFrameType()</h2>
|
||||
|
||||
<div class="memitem">
|
||||
<div class="memproto">
|
||||
<table class="memname">
|
||||
<tr>
|
||||
<td class="memname"><a class="el" href="constants_8h.html#a2cadd9c064904e21e2acd0d0f64ad8b6">U_FrameType</a> parseFrameType </td>
|
||||
<td>(</td>
|
||||
<td class="paramtype">uint8_t * </td>
|
||||
<td class="paramname"><em>d</em></td><td>)</td>
|
||||
<td></td>
|
||||
</tr>
|
||||
</table>
|
||||
</div><div class="memdoc">
|
||||
|
||||
<p>extracts frametype from data package </p>
|
||||
<dl class="params"><dt>Parameters</dt><dd>
|
||||
<table class="params">
|
||||
<tr><td class="paramname">d</td><td>data package </td></tr>
|
||||
</table>
|
||||
</dd>
|
||||
</dl>
|
||||
<dl class="section return"><dt>Returns</dt><dd>U_FrameType </dd></dl>
|
||||
<div class="dynheader">
|
||||
Here is the caller graph for this function:</div>
|
||||
<div class="dyncontent">
|
||||
<div class="center"><img src="UARTCom_8cpp_a5bfcc9a4d05eaa07aff6dbc5ffbc01a4_icgraph.png" border="0" usemap="#aUARTCom_8cpp_a5bfcc9a4d05eaa07aff6dbc5ffbc01a4_icgraph" alt=""/></div>
|
||||
<map name="aUARTCom_8cpp_a5bfcc9a4d05eaa07aff6dbc5ffbc01a4_icgraph" id="aUARTCom_8cpp_a5bfcc9a4d05eaa07aff6dbc5ffbc01a4_icgraph">
|
||||
<area shape="rect" title="extracts frametype from data package" alt="" coords="445,5,575,32"/>
|
||||
<area shape="rect" href="UARTCom_8cpp.html#a86f7112e2f3c0cf6e89e6cc9ce0d35bc" title="package handler, checks for errors first, then proceeds to extract information from the data package" alt="" coords="276,5,397,32"/>
|
||||
<area shape="rect" href="classUARTCom.html#a38e053e8c8bcad7735c7fe09bfc84ffd" title="reads uart interface and stores the data into an uint8_t array" alt="" coords="104,5,228,32"/>
|
||||
<area shape="rect" href="main_8cpp.html#a0b33edabd7f1c4e4a0bf32c67269be2f" title=" " alt="" coords="5,5,56,32"/>
|
||||
</map>
|
||||
</div>
|
||||
|
||||
</div>
|
||||
</div>
|
||||
<a id="a67a111cec96745786304360702d7fb0d"></a>
|
||||
<h2 class="memtitle"><span class="permalink"><a href="#a67a111cec96745786304360702d7fb0d">◆ </a></span>parseRequest()</h2>
|
||||
|
||||
<div class="memitem">
|
||||
<div class="memproto">
|
||||
<table class="memname">
|
||||
<tr>
|
||||
<td class="memname"><a class="el" href="constants_8h.html#a83703b84abb8c92901ec1c15e0bbad80">U_Request</a> parseRequest </td>
|
||||
<td>(</td>
|
||||
<td class="paramtype">uint8_t * </td>
|
||||
<td class="paramname"><em>d</em></td><td>)</td>
|
||||
<td></td>
|
||||
</tr>
|
||||
</table>
|
||||
</div><div class="memdoc">
|
||||
|
||||
<p>extracts request information from data package </p>
|
||||
<dl class="params"><dt>Parameters</dt><dd>
|
||||
<table class="params">
|
||||
<tr><td class="paramname">d</td><td>data package </td></tr>
|
||||
</table>
|
||||
</dd>
|
||||
</dl>
|
||||
<dl class="section return"><dt>Returns</dt><dd>U_Request </dd></dl>
|
||||
<div class="dynheader">
|
||||
Here is the caller graph for this function:</div>
|
||||
<div class="dyncontent">
|
||||
<div class="center"><img src="UARTCom_8cpp_a67a111cec96745786304360702d7fb0d_icgraph.png" border="0" usemap="#aUARTCom_8cpp_a67a111cec96745786304360702d7fb0d_icgraph" alt=""/></div>
|
||||
<map name="aUARTCom_8cpp_a67a111cec96745786304360702d7fb0d_icgraph" id="aUARTCom_8cpp_a67a111cec96745786304360702d7fb0d_icgraph">
|
||||
<area shape="rect" title="extracts request information from data package" alt="" coords="612,5,723,32"/>
|
||||
<area shape="rect" href="UARTCom_8cpp.html#a8f3f9f5697687756152cfc8045170646" title="executes commands according to incoming request" alt="" coords="445,5,564,32"/>
|
||||
<area shape="rect" href="UARTCom_8cpp.html#a86f7112e2f3c0cf6e89e6cc9ce0d35bc" title="package handler, checks for errors first, then proceeds to extract information from the data package" alt="" coords="276,5,397,32"/>
|
||||
<area shape="rect" href="classUARTCom.html#a38e053e8c8bcad7735c7fe09bfc84ffd" title="reads uart interface and stores the data into an uint8_t array" alt="" coords="104,5,228,32"/>
|
||||
<area shape="rect" href="main_8cpp.html#a0b33edabd7f1c4e4a0bf32c67269be2f" title=" " alt="" coords="5,5,56,32"/>
|
||||
</map>
|
||||
</div>
|
||||
|
||||
</div>
|
||||
</div>
|
||||
<a id="ac85d37d78756559b8b923544852dd430"></a>
|
||||
<h2 class="memtitle"><span class="permalink"><a href="#ac85d37d78756559b8b923544852dd430">◆ </a></span>parseTimestamp()</h2>
|
||||
|
||||
<div class="memitem">
|
||||
<div class="memproto">
|
||||
<table class="memname">
|
||||
<tr>
|
||||
<td class="memname">uint32_t parseTimestamp </td>
|
||||
<td>(</td>
|
||||
<td class="paramtype">uint8_t * </td>
|
||||
<td class="paramname"><em>d</em></td><td>)</td>
|
||||
<td></td>
|
||||
</tr>
|
||||
</table>
|
||||
</div><div class="memdoc">
|
||||
|
||||
<p>extracts timestamp from data package </p>
|
||||
<dl class="params"><dt>Parameters</dt><dd>
|
||||
<table class="params">
|
||||
<tr><td class="paramname">d</td><td>data package </td></tr>
|
||||
</table>
|
||||
</dd>
|
||||
</dl>
|
||||
<dl class="section return"><dt>Returns</dt><dd>uint32_t </dd></dl>
|
||||
<div class="dynheader">
|
||||
Here is the call graph for this function:</div>
|
||||
<div class="dyncontent">
|
||||
<div class="center"><img src="UARTCom_8cpp_ac85d37d78756559b8b923544852dd430_cgraph.png" border="0" usemap="#aUARTCom_8cpp_ac85d37d78756559b8b923544852dd430_cgraph" alt=""/></div>
|
||||
<map name="aUARTCom_8cpp_ac85d37d78756559b8b923544852dd430_cgraph" id="aUARTCom_8cpp_ac85d37d78756559b8b923544852dd430_cgraph">
|
||||
<area shape="rect" title="extracts timestamp from data package" alt="" coords="5,5,136,32"/>
|
||||
<area shape="rect" href="classUtils.html#a994ae9cd902090355b4777f0dd28e95c" title="converts 4 bytes to uint32_t (big endian)" alt="" coords="184,5,311,32"/>
|
||||
</map>
|
||||
</div>
|
||||
|
||||
</div>
|
||||
</div>
|
||||
<a id="ac77fffc0c7f612ccf0db14af856e3277"></a>
|
||||
<h2 class="memtitle"><span class="permalink"><a href="#ac77fffc0c7f612ccf0db14af856e3277">◆ </a></span>showPackage()</h2>
|
||||
|
||||
<div class="memitem">
|
||||
<div class="memproto">
|
||||
<table class="memname">
|
||||
<tr>
|
||||
<td class="memname">void showPackage </td>
|
||||
<td>(</td>
|
||||
<td class="paramtype">uint8_t * </td>
|
||||
<td class="paramname"><em>d</em>, </td>
|
||||
</tr>
|
||||
<tr>
|
||||
<td class="paramkey"></td>
|
||||
<td></td>
|
||||
<td class="paramtype">int </td>
|
||||
<td class="paramname"><em>pl</em> </td>
|
||||
</tr>
|
||||
<tr>
|
||||
<td></td>
|
||||
<td>)</td>
|
||||
<td></td><td></td>
|
||||
</tr>
|
||||
</table>
|
||||
</div><div class="memdoc">
|
||||
|
||||
<p>debugging function, prints out package data </p>
|
||||
<dl class="params"><dt>Parameters</dt><dd>
|
||||
<table class="params">
|
||||
<tr><td class="paramname">d</td><td>data package </td></tr>
|
||||
<tr><td class="paramname">pl</td><td>payload length </td></tr>
|
||||
</table>
|
||||
</dd>
|
||||
</dl>
|
||||
<div class="dynheader">
|
||||
Here is the caller graph for this function:</div>
|
||||
<div class="dyncontent">
|
||||
<div class="center"><img src="UARTCom_8cpp_ac77fffc0c7f612ccf0db14af856e3277_icgraph.png" border="0" usemap="#aUARTCom_8cpp_ac77fffc0c7f612ccf0db14af856e3277_icgraph" alt=""/></div>
|
||||
<map name="aUARTCom_8cpp_ac77fffc0c7f612ccf0db14af856e3277_icgraph" id="aUARTCom_8cpp_ac77fffc0c7f612ccf0db14af856e3277_icgraph">
|
||||
<area shape="rect" title="debugging function, prints out package data" alt="" coords="445,5,556,32"/>
|
||||
<area shape="rect" href="UARTCom_8cpp.html#a86f7112e2f3c0cf6e89e6cc9ce0d35bc" title="package handler, checks for errors first, then proceeds to extract information from the data package" alt="" coords="276,5,397,32"/>
|
||||
<area shape="rect" href="classUARTCom.html#a38e053e8c8bcad7735c7fe09bfc84ffd" title="reads uart interface and stores the data into an uint8_t array" alt="" coords="104,5,228,32"/>
|
||||
<area shape="rect" href="main_8cpp.html#a0b33edabd7f1c4e4a0bf32c67269be2f" title=" " alt="" coords="5,5,56,32"/>
|
||||
</map>
|
||||
</div>
|
||||
|
||||
</div>
|
||||
</div>
|
||||
<h2 class="groupheader">Variable Documentation</h2>
|
||||
<a id="aa786999c8aa65490b5b03fb09a9f1f98"></a>
|
||||
<h2 class="memtitle"><span class="permalink"><a href="#aa786999c8aa65490b5b03fb09a9f1f98">◆ </a></span>currentParseIndex</h2>
|
||||
|
||||
<div class="memitem">
|
||||
<div class="memproto">
|
||||
<table class="memname">
|
||||
<tr>
|
||||
<td class="memname">uint8_t currentParseIndex</td>
|
||||
</tr>
|
||||
</table>
|
||||
</div><div class="memdoc">
|
||||
|
||||
</div>
|
||||
</div>
|
||||
<a id="aae4c1b8c8e6cca37d95276b38497b370"></a>
|
||||
<h2 class="memtitle"><span class="permalink"><a href="#aae4c1b8c8e6cca37d95276b38497b370">◆ </a></span>currentTimestamp</h2>
|
||||
|
||||
<div class="memitem">
|
||||
<div class="memproto">
|
||||
<table class="memname">
|
||||
<tr>
|
||||
<td class="memname">uint32_t currentTimestamp = 0</td>
|
||||
</tr>
|
||||
</table>
|
||||
</div><div class="memdoc">
|
||||
|
||||
</div>
|
||||
</div>
|
||||
<a id="a2eead10869c5f921ef036aa656683cd5"></a>
|
||||
<h2 class="memtitle"><span class="permalink"><a href="#a2eead10869c5f921ef036aa656683cd5">◆ </a></span>payloadLength</h2>
|
||||
|
||||
<div class="memitem">
|
||||
<div class="memproto">
|
||||
<table class="memname">
|
||||
<tr>
|
||||
<td class="memname">int payloadLength</td>
|
||||
</tr>
|
||||
</table>
|
||||
</div><div class="memdoc">
|
||||
|
||||
</div>
|
||||
</div>
|
||||
<a id="adeaeefb426fbd7c5a72fffec28ee0c46"></a>
|
||||
<h2 class="memtitle"><span class="permalink"><a href="#adeaeefb426fbd7c5a72fffec28ee0c46">◆ </a></span>wheelLeft</h2>
|
||||
|
||||
<div class="memitem">
|
||||
<div class="memproto">
|
||||
<table class="mlabels">
|
||||
<tr>
|
||||
<td class="mlabels-left">
|
||||
<table class="memname">
|
||||
<tr>
|
||||
<td class="memname">MotorWheel wheelLeft</td>
|
||||
</tr>
|
||||
</table>
|
||||
</td>
|
||||
<td class="mlabels-right">
|
||||
<span class="mlabels"><span class="mlabel">extern</span></span> </td>
|
||||
</tr>
|
||||
</table>
|
||||
</div><div class="memdoc">
|
||||
|
||||
</div>
|
||||
</div>
|
||||
<a id="a5ab69515b5724f039c137585cbf24787"></a>
|
||||
<h2 class="memtitle"><span class="permalink"><a href="#a5ab69515b5724f039c137585cbf24787">◆ </a></span>wheelRight</h2>
|
||||
|
||||
<div class="memitem">
|
||||
<div class="memproto">
|
||||
<table class="mlabels">
|
||||
<tr>
|
||||
<td class="mlabels-left">
|
||||
<table class="memname">
|
||||
<tr>
|
||||
<td class="memname">MotorWheel wheelRight</td>
|
||||
</tr>
|
||||
</table>
|
||||
</td>
|
||||
<td class="mlabels-right">
|
||||
<span class="mlabels"><span class="mlabel">extern</span></span> </td>
|
||||
</tr>
|
||||
</table>
|
||||
</div><div class="memdoc">
|
||||
|
||||
</div>
|
||||
</div>
|
||||
</div><!-- contents -->
|
||||
<!-- start footer part -->
|
||||
<hr class="footer"/><address class="footer"><small>
|
||||
Generated by <a href="https://www.doxygen.org/index.html"><img class="footer" src="doxygen.svg" width="104" height="31" alt="doxygen"/></a> 1.9.1
|
||||
</small></address>
|
||||
</body>
|
||||
</html>
|
@ -1,10 +0,0 @@
|
||||
<map id="src/communication/UARTCom.cpp" name="src/communication/UARTCom.cpp">
|
||||
<area shape="rect" id="node1" title=" " alt="" coords="465,5,708,32"/>
|
||||
<area shape="rect" id="node2" href="$UARTCom_8hpp.html" title="class to manage uart communication" alt="" coords="145,80,365,107"/>
|
||||
<area shape="rect" id="node4" href="$constants_8h.html" title=" " alt="" coords="538,155,635,181"/>
|
||||
<area shape="rect" id="node5" href="$UCommands_8hpp.html" title="implementation of commands according to uart protocol" alt="" coords="389,80,627,107"/>
|
||||
<area shape="rect" id="node6" href="$UValue_8hpp.html" title="class to send out encoder values" alt="" coords="703,80,905,107"/>
|
||||
<area shape="rect" id="node7" href="$Utils_8hpp.html" title="useful converting and computing functions" alt="" coords="5,80,120,107"/>
|
||||
<area shape="rect" id="node8" title=" " alt="" coords="930,80,1043,107"/>
|
||||
<area shape="rect" id="node3" title=" " alt="" coords="213,155,297,181"/>
|
||||
</map>
|
@ -1 +0,0 @@
|
||||
8b43cfce26cd8ba8d473af14768ad42c
|
Before Width: | Height: | Size: 27 KiB |
@ -1,11 +0,0 @@
|
||||
<map id="fromComponent" name="fromComponent">
|
||||
<area shape="rect" id="node1" title="translates component into byte value" alt="" coords="1069,56,1197,83"/>
|
||||
<area shape="rect" id="node2" href="$classUARTCom.html#a7d317999b89947edc57ba32012c9522f" title="assembles and sends a uart package" alt="" coords="895,56,1021,83"/>
|
||||
<area shape="rect" id="node3" href="$classUValue.html#a92218410a1f6b266c142fe4f2af704ae" title="send both encoder values via uart" alt="" coords="612,5,847,32"/>
|
||||
<area shape="rect" id="node8" href="$classUValue.html#ac1818040e6bca1803b368b958db7333b" title="sends encoder value via uart" alt="" coords="631,56,828,83"/>
|
||||
<area shape="rect" id="node9" href="$main_8cpp.html#a7dfd9b79bc5a37d7df40207afbc5431f" title=" " alt="" coords="700,107,759,133"/>
|
||||
<area shape="rect" id="node4" href="$UARTCom_8cpp.html#a8f3f9f5697687756152cfc8045170646" title="executes commands according to incoming request" alt="" coords="445,5,564,32"/>
|
||||
<area shape="rect" id="node5" href="$UARTCom_8cpp.html#a86f7112e2f3c0cf6e89e6cc9ce0d35bc" title="package handler, checks for errors first, then proceeds to extract information from the data package" alt="" coords="276,5,397,32"/>
|
||||
<area shape="rect" id="node6" href="$classUARTCom.html#a38e053e8c8bcad7735c7fe09bfc84ffd" title="reads uart interface and stores the data into an uint8_t array" alt="" coords="104,5,228,32"/>
|
||||
<area shape="rect" id="node7" href="$main_8cpp.html#a0b33edabd7f1c4e4a0bf32c67269be2f" title=" " alt="" coords="5,5,56,32"/>
|
||||
</map>
|
@ -1 +0,0 @@
|
||||
8e92de5ae4e7cd9be27aa5cbc06b6401
|
Before Width: | Height: | Size: 15 KiB |
@ -1,4 +0,0 @@
|
||||
<map id="correctChecksum" name="correctChecksum">
|
||||
<area shape="rect" id="node1" title="checks if checksum inside package and computed checksum from package data are the same" alt="" coords="5,5,140,32"/>
|
||||
<area shape="rect" id="node2" href="$UARTCom_8cpp.html#a744c5a2f1e07b896f5dc1a3b352dfd2a" title="computes checksum from data package" alt="" coords="188,5,335,32"/>
|
||||
</map>
|
@ -1 +0,0 @@
|
||||
13351d7ac34c422f0730ac91d9aaace4
|
Before Width: | Height: | Size: 3.4 KiB |
@ -1,6 +0,0 @@
|
||||
<map id="correctChecksum" name="correctChecksum">
|
||||
<area shape="rect" id="node1" title="checks if checksum inside package and computed checksum from package data are the same" alt="" coords="445,5,580,32"/>
|
||||
<area shape="rect" id="node2" href="$UARTCom_8cpp.html#a86f7112e2f3c0cf6e89e6cc9ce0d35bc" title="package handler, checks for errors first, then proceeds to extract information from the data package" alt="" coords="276,5,397,32"/>
|
||||
<area shape="rect" id="node3" href="$classUARTCom.html#a38e053e8c8bcad7735c7fe09bfc84ffd" title="reads uart interface and stores the data into an uint8_t array" alt="" coords="104,5,228,32"/>
|
||||
<area shape="rect" id="node4" href="$main_8cpp.html#a0b33edabd7f1c4e4a0bf32c67269be2f" title=" " alt="" coords="5,5,56,32"/>
|
||||
</map>
|
@ -1 +0,0 @@
|
||||
631f259c2881c7c8c1599e505e57ca70
|
Before Width: | Height: | Size: 5.0 KiB |
@ -1,7 +0,0 @@
|
||||
<map id="clearPackage" name="clearPackage">
|
||||
<area shape="rect" id="node1" title="erases all package data and sets the array to 0" alt="" coords="284,31,393,57"/>
|
||||
<area shape="rect" id="node2" href="$classUARTCom.html#a0b8f43f58c7ed25f191a0339ad0f170d" title="initializes uart communication" alt="" coords="116,5,232,32"/>
|
||||
<area shape="rect" id="node4" href="$classUARTCom.html#a38e053e8c8bcad7735c7fe09bfc84ffd" title="reads uart interface and stores the data into an uint8_t array" alt="" coords="112,56,236,83"/>
|
||||
<area shape="rect" id="node3" href="$main_8cpp.html#a7dfd9b79bc5a37d7df40207afbc5431f" title=" " alt="" coords="5,5,64,32"/>
|
||||
<area shape="rect" id="node5" href="$main_8cpp.html#a0b33edabd7f1c4e4a0bf32c67269be2f" title=" " alt="" coords="9,56,60,83"/>
|
||||
</map>
|
@ -1 +0,0 @@
|
||||
daa4574a1b6bc521fbdedeef2ef3a792
|