Robotics StackExchange | Archived questions

Model not displayed on Gazebo

Hello. This may be a little confusing because I am using a translator.

I was trying to simulate my robot using Gazebo and MoveIt2. I can use Rviz to view models from urdf files, and I can use MoveIt2 and Rviz for planning, but I just can't get Gazebo to display them.

Here is the urdf file, the launch file, and the results of the run.Please, could you think together with me? After I spawn an entity, gzserver freezes for about 2 minutes, and then I can see the joints, controllers, etc. in Gazebo, but the model does not show up.

image

waiting gazebo:
image


$ env | grep ROS

ROS_VERSION=2  
ROS_PYTHON_VERSION=3  
ROS_LOCALHOST_ONLY=0  
ROS_DISTRO=humble  

Execution Result Log

tsumu@MONDAY-UBUNTU-LAPTOP:~/ros-humble/dexterous_hand_v1_ws$ ros2 launch dexterous_hand_v1_gazebo_ros2_control arm.launch.py   
 [INFO] [launch]: All log files can be found below /home/tsumu/.ros/log/2023-04-05-20-20-33-857012-MONDAY-UBUNTU-LAPTOP-6119  
 [INFO] [launch]: Default logging verbosity is set to INFO  
 [INFO] [gzserver-1]: process started with pid [6120]  
 [INFO] [gzclient-2]: process started with pid [6122]  
 [INFO] [robot_state_publisher-3]: process started with pid [6124]  
 [INFO] [spawn_entity.py-4]: process started with pid [6126]  
 [robot_state_publisher-3] [INFO] [1680693634.338109509] [robot_state_publisher]: got segment base_link  
 [robot_state_publisher-3] [INFO] [1680693634.338220516] [robot_state_publisher]: got segment dummy  
 [robot_state_publisher-3] [INFO] [1680693634.338231817] [robot_state_publisher]: got segment forth_link_1  
 [robot_state_publisher-3] [INFO] [1680693634.338238713] [robot_state_publisher]: got segment second_link_1  
 [robot_state_publisher-3] [INFO] [1680693634.338244831] [robot_state_publisher]: got segment third_link_1  
 [spawn_entity.py-4] [INFO] [1680693634.715247842] [spawn_entity]: Spawn Entity started  
 [spawn_entity.py-4] [INFO] [1680693634.715531098] [spawn_entity]: Loading entity published on topic robot_description  
 [spawn_entity.py-4] /opt/ros/humble/local/lib/python3.10/dist-packages/rclpy/qos.py:307: UserWarning: DurabilityPolicy.RMW_QOS_POLICY_DURABILITY_TRANSIENT_LOCAL is deprecated. Use DurabilityPolicy.TRANSIENT_LOCAL instead.  
 [spawn_entity.py-4]   warnings.warn(  
 [spawn_entity.py-4] [INFO] [1680693634.716870559] [spawn_entity]: Waiting for entity xml on robot_description  
 [spawn_entity.py-4] [INFO] [1680693634.823384964] [spawn_entity]: Waiting for service /spawn_entity, timeout = 30  
 [spawn_entity.py-4] [INFO] [1680693634.823616607] [spawn_entity]: Waiting for service /spawn_entity  
 [spawn_entity.py-4] [INFO] [1680693635.577584619] [spawn_entity]: Calling service /spawn_entity  
 [spawn_entity.py-4] [INFO] [1680693635.669593639] [spawn_entity]: Spawn status: SpawnEntity: Successfully spawned entity [dexterous_hand_v1]  
 [INFO] [spawn_entity.py-4]: process has finished cleanly [pid 6126]  

==========================================================
It freezes here for about 2 minutes, and then the following log flows at once
==========================================================

 [gzserver-1] [INFO] [1680693751.423159905] [gazebo_ros2_control]: Loading gazebo_ros2_control plugin  
 [gzserver-1] [INFO] [1680693751.425924060] [gazebo_ros2_control]: Starting gazebo_ros2_control plugin in namespace: /  
 [gzserver-1] [INFO] [1680693751.426113717] [gazebo_ros2_control]: Starting gazebo_ros2_control plugin in ros 2 node: gazebo_ros2_control  
 [gzserver-1] [INFO] [1680693751.426161078] [gazebo_ros2_control]: Loading parameter files /home/tsumu/ros-humble/dexterous_hand_v1_ws/install/dexterous_hand_v1_gazebo_ros2_control/share/dexterous_hand_v1_gazebo_ros2_control/config/dexterous_hand_v1_move_group_controller.yaml  
 [gzserver-1] [INFO] [1680693751.467614275] [gazebo_ros2_control]: connected to service!! robot_state_publisher  
 [gzserver-1] [INFO] [1680693751.467908923] [gazebo_ros2_control]: Recieved urdf from param server, parsing...  
 [gzserver-1] [INFO] [1680693751.475137434] [gazebo_ros2_control]: Loading joint: joint1  
 [gzserver-1] [INFO] [1680693751.475172459] [gazebo_ros2_control]:  State:  
 [gzserver-1] [INFO] [1680693751.475179512] [gazebo_ros2_control]:       position  
 [gzserver-1] [INFO] [1680693751.475186286] [gazebo_ros2_control]:           found initial value: 0.000000  
 [gzserver-1] [INFO] [1680693751.475193915] [gazebo_ros2_control]:       velocity  
 [gzserver-1] [INFO] [1680693751.475198683] [gazebo_ros2_control]:  Command:  
 [gzserver-1] [INFO] [1680693751.475204052] [gazebo_ros2_control]:       position  
 [gzserver-1] [INFO] [1680693751.475483117] [gazebo_ros2_control]: Loading joint: joint2  
 [gzserver-1] [INFO] [1680693751.475489250] [gazebo_ros2_control]:  State:  
 [gzserver-1] [INFO] [1680693751.475493510] [gazebo_ros2_control]:       position  
 [gzserver-1] [INFO] [1680693751.475497505] [gazebo_ros2_control]:           found initial value: 0.000000  
 [gzserver-1] [INFO] [1680693751.475502569] [gazebo_ros2_control]:       velocity  
 [gzserver-1] [INFO] [1680693751.475506598] [gazebo_ros2_control]:  Command:  
 [gzserver-1] [INFO] [1680693751.475510562] [gazebo_ros2_control]:       position  
 [gzserver-1] [INFO] [1680693751.475516826] [gazebo_ros2_control]: Loading joint: joint3  
 [gzserver-1] [INFO] [1680693751.475521130] [gazebo_ros2_control]:  State:  
 [gzserver-1] [INFO] [1680693751.475525416] [gazebo_ros2_control]:       position  
 [gzserver-1] [INFO] [1680693751.475529180] [gazebo_ros2_control]:           found initial value: 0.000000  
 [gzserver-1] [INFO] [1680693751.475533725] [gazebo_ros2_control]:       velocity  
 [gzserver-1] [INFO] [1680693751.475537793] [gazebo_ros2_control]:  Command:  
 [gzserver-1] [INFO] [1680693751.475541677] [gazebo_ros2_control]:       position  
 [gzserver-1] [INFO] [1680693751.475570883] [resource_manager]: Initialize hardware 'GazeboSystem'   
 [gzserver-1] [INFO] [1680693751.475636782] [resource_manager]: Successful initialization of hardware 'GazeboSystem'  
 [gzserver-1] [INFO] [1680693751.475679608] [resource_manager]: 'configure' hardware 'GazeboSystem'   
 [gzserver-1] [INFO] [1680693751.475682843] [resource_manager]: Successful 'configure' of hardware 'GazeboSystem'  
 [gzserver-1] [INFO] [1680693751.475686166] [resource_manager]: 'activate' hardware 'GazeboSystem'   
 [gzserver-1] [INFO] [1680693751.475689065] [resource_manager]: Successful 'activate' of hardware 'GazeboSystem'  
 [gzserver-1] [INFO] [1680693751.475733215] [gazebo_ros2_control]: Loading controller_manager  
 [gzserver-1] [WARN] [1680693751.488964516] [gazebo_ros2_control]:  Desired controller update period (0.1 s) is slower than the gazebo simulation period (0.001 s).  
 [gzserver-1] [INFO] [1680693751.489138466] [gazebo_ros2_control]: Loaded gazebo_ros2_control.  
 [INFO] [ros2-5]: process started with pid [6949]  
 [gzserver-1] [INFO] [1680693756.938269117] [controller_manager]: Loading controller 'joint_state_broadcaster'  
 [gzserver-1] [INFO] [1680693756.964620413] [controller_manager]: Setting use_sim_time=True for joint_state_broadcaster to match controller manager (see ros2_control#325 for details)  
 [gzserver-1] [INFO] [1680693757.040278375] [controller_manager]: Configuring controller 'joint_state_broadcaster'  
 [gzserver-1] [INFO] [1680693757.040513829] [joint_state_broadcaster]: 'joints' or 'interfaces' parameter is empty. All available state interfaces will be published  
 [ros2-5] Sucessfully loaded controller joint_state_broadcaster into state active  
 [INFO] [ros2-5]: process has finished cleanly [pid 6949]  
 [INFO] [ros2-6]: process started with pid [6977]  
 [gzserver-1] [INFO] [1680693758.177732230] [controller_manager]: Loading controller 'arm_controller'  
 [gzserver-1] [INFO] [1680693758.199640459] [controller_manager]: Setting use_sim_time=True for arm_controller to match controller manager (see ros2_control#325 for details)  
 [gzserver-1] [INFO] [1680693758.247520967] [controller_manager]: Configuring controller 'arm_controller'  
 [gzserver-1] [INFO] [1680693758.247647868] [arm_controller]: No specific joint names are used for command interfaces. Using 'joints' parameter.  
 [gzserver-1] [INFO] [1680693758.247677102] [arm_controller]: Command interfaces are [position] and state interfaces are [position velocity].  
 [gzserver-1] [INFO] [1680693758.247720304] [arm_controller]: Using 'splines' interpolation method.  
 [gzserver-1] [INFO] [1680693758.248572104] [arm_controller]: Controller state will be published at 50.00 Hz.  
 [gzserver-1] [INFO] [1680693758.249275079] [arm_controller]: Action status changes will be monitored at 20.00 Hz.  
 [ros2-6] Sucessfully loaded controller arm_controller into state active  
 [INFO] [ros2-6]: process has finished cleanly [pid 6977]

arm_launch.py

import os  

from ament_index_python.packages import get_package_share_directory  


from launch import LaunchDescription  
from launch.actions import ExecuteProcess, IncludeLaunchDescription, RegisterEventHandler, TimerAction  
from launch.event_handlers import OnProcessExit  
from launch.launch_description_sources import PythonLaunchDescriptionSource  
from launch_ros.substitutions import FindPackageShare  
from launch_ros.actions import Node  

import xacro  


def generate_launch_description():  
    # Constants for paths to different files and folders  
    gazebo_pkg_name = 'dexterous_hand_v1_gazebo_ros2_control'  
    world_file_path = 'worlds/basic.world'  

    # Pose where we want to spawn the robot  
    spawn_x_val = '0.0'  
    spawn_y_val = '0.0'  
    spawn_z_val = '0.0'  
    spawn_yaw_val = '0.0'  

    gazebo_pkg_share = FindPackageShare(package=gazebo_pkg_name).find(gazebo_pkg_name)  
    world_path = os.path.join(gazebo_pkg_share, world_file_path)  

    gazebo = IncludeLaunchDescription(  
                PythonLaunchDescriptionSource([os.path.join(  
                    get_package_share_directory('gazebo_ros'), 'launch'), '/gazebo.launch.py']),  
                    launch_arguments={'world': world_path}.items(),  
             )  

    dexterous_hand_v1_gazebo_ros2_control_path = os.path.join(  
        get_package_share_directory('dexterous_hand_v1_gazebo_ros2_control'))  

    xacro_file = os.path.join(dexterous_hand_v1_gazebo_ros2_control_path,  
                              'config',  
                              'dexterous_hand_v1.xacro.urdf')  

    doc = xacro.parse(open(xacro_file))  
    xacro.process_doc(doc)  
    params = {'robot_description': doc.toxml()}  

    node_robot_state_publisher = Node(  
        package='robot_state_publisher',  
        executable='robot_state_publisher',  
        output='screen',  
        parameters=[params]  
    )  

    spawn_entity = Node(package='gazebo_ros', executable='spawn_entity.py',  
                        arguments=['-topic', 'robot_description',  
                                   '-entity', 'dexterous_hand_v1',  
                                   '-x', spawn_x_val,  
                                   '-y', spawn_y_val,  
                                   '-z', spawn_z_val,  
                                   '-Y', spawn_yaw_val,  
                                   ],  
                        output='screen')  

    load_joint_state_broadcaster = ExecuteProcess(  
        cmd=['ros2', 'control', 'load_controller', '--set-state', 'active',  
             'joint_state_broadcaster'],  
        output='screen'  
    )  

    load_arm_controller = ExecuteProcess(  
        cmd=['ros2', 'control', 'load_controller', '--set-state', 'active', 'arm_controller'],  
        output='screen'  
    )  

    return LaunchDescription([  
        RegisterEventHandler(  
            event_handler=OnProcessExit(  
                target_action=spawn_entity,  
                on_exit=[  
                    # Because Gazebo freezes for 2 min.  
                    TimerAction(  
                        period=120.0,  
                        actions=[load_joint_state_broadcaster]  
                    )  
                ],  
            )  
        ),  
        RegisterEventHandler(  
            event_handler=OnProcessExit(  
                target_action=load_joint_state_broadcaster,  
                on_exit=[load_arm_controller],  
            )  
        ),  
        gazebo,  
        node_robot_state_publisher,  
        spawn_entity,  
    ])  

dexterous_hand_v1_move_group_controller.yaml

# This config file is used by ros2_control  
 controller_manager:  
   ros__parameters:  
     update_rate: 100  # Hz  

     arm_controller:  
       type: joint_trajectory_controller/JointTrajectoryController  


     joint_state_broadcaster:  
       type: joint_state_broadcaster/JointStateBroadcaster  


 arm_controller:  
   ros__parameters:  
     joints:  
       - joint1  
       - joint2  
       - joint3  
     command_interfaces:  
       - position  
     state_interfaces:  
       - position  
       - velocity

urdf file

<?xml version="1.0" ?>  
 <!-- =================================================================================== -->  
 <!-- |    This document was autogenerated by xacro from dexterous_hand_v1.xacro        | -->  
 <!-- |    EDITING THIS FILE BY HAND IS NOT RECOMMENDED                                 | -->  
 <!-- =================================================================================== -->  
 <robot name="dexterous_hand_v1">  
   <material name="silver_default">  
     <color rgba="0.700 0.700 0.700 1.000"/>  
   </material>  
   <material name="_">  
     <color rgba="0.6274509803921569 0.6274509803921569 0.6274509803921569 1.0"/>  
   </material>  
   <material name="opaque636363">  
     <color rgba="0.25098039215686274 0.25098039215686274 0.25098039215686274 1.0"/>  
   </material>  
   <material name="tough_2000_formlabs_sla_3d_">  
     <color rgba="0.24705882352941178 0.24705882352941178 0.24705882352941178 1.0"/>  
   </material>  
   <transmission name="joint1_tran">  
     <type>transmission_interface/SimpleTransmission</type>  
     <joint name="joint1">  
       <hardwareInterface>hardware_interface/EffortJointInterface</hardwareInterface>  
     </joint>  
     <actuator name="joint1_actr">  
       <hardwareInterface>hardware_interface/EffortJointInterface</hardwareInterface>  
       <mechanicalReduction>1</mechanicalReduction>  
     </actuator>  
   </transmission>  
   <transmission name="joint2_tran">  
     <type>transmission_interface/SimpleTransmission</type>  
     <joint name="joint2">  
       <hardwareInterface>hardware_interface/EffortJointInterface</hardwareInterface>  
     </joint>  
     <actuator name="joint2_actr">  
       <hardwareInterface>hardware_interface/EffortJointInterface</hardwareInterface>  
       <mechanicalReduction>1</mechanicalReduction>  
     </actuator>  
   </transmission>  
   <transmission name="joint3_tran">  
     <type>transmission_interface/SimpleTransmission</type>  
     <joint name="joint3">  
       <hardwareInterface>hardware_interface/EffortJointInterface</hardwareInterface>  
     </joint>  
     <actuator name="joint3_actr">  
       <hardwareInterface>hardware_interface/EffortJointInterface</hardwareInterface>  
       <mechanicalReduction>1</mechanicalReduction>  
     </actuator>  
   </transmission>  
   <link name="dummy">  
 </link>  
   <link name="base_link">  
     <inertial>  
       <origin rpy="0 0 0" xyz="4.277886270075532e-15 5.651037530697169e-21 0.036748407084489725"/>  
       <mass value="1.5422390483101742"/>  
       <inertia ixx="0.001054" ixy="-0.0" ixz="-0.0" iyy="0.001054" iyz="-0.0" izz="0.000635"/>  
     </inertial>  
     <visual>  
       <origin rpy="0 0 0" xyz="0 0 0"/>  
       <geometry>  
         <mesh filename="package://dexterous_hand_v1_description/meshes/base_link.stl" scale="0.001 0.001 0.001"/>  
       </geometry>  
       <material name="_"/>  
     </visual>  
     <collision>  
       <origin rpy="0 0 0" xyz="0 0 0"/>  
       <geometry>  
         <mesh filename="package://dexterous_hand_v1_description/meshes/base_link.stl" scale="0.001 0.001 0.001"/>  
       </geometry>  
     </collision>  
   </link>  
   <link name="second_link_1">  
     <inertial>  
       <origin rpy="0 0 0" xyz="0.004007100501992406 3.083339112935745e-06 0.03834403736565162"/>  
       <mass value="1.3110327852879664"/>  
       <inertia ixx="0.001046" ixy="-0.0" ixz="-2.6e-05" iyy="0.001126" iyz="-0.0" izz="0.000386"/>  
     </inertial>  
     <visual>  
       <origin rpy="0 0 0" xyz="-0.0 -0.0 -0.0789"/>  
       <geometry>  
         <mesh filename="package://dexterous_hand_v1_description/meshes/second_link_1.stl" scale="0.001 0.001 0.001"/>  
       </geometry>  
       <material name="opaque636363"/>  
     </visual>  
     <collision>  
       <origin rpy="0 0 0" xyz="-0.0 -0.0 -0.0789"/>  
       <geometry>  
         <mesh filename="package://dexterous_hand_v1_description/meshes/second_link_1.stl" scale="0.001 0.001 0.001"/>  
       </geometry>  
     </collision>  
   </link>  
   <link name="third_link_1">  
     <inertial>  
       <origin rpy="0 0 0" xyz="-0.01726771323226515 0.00050778137353055 0.019266992722896975"/>  
       <mass value="0.11379886357544111"/>  
       <inertia ixx="5e-05" ixy="0.0" ixz="0.0" iyy="4.7e-05" iyz="-1e-06" izz="4.8e-05"/>  
     </inertial>  
     <visual>  
       <origin rpy="0 0 0" xyz="-0.0229 -1.5e-05 -0.164229"/>  
       <geometry>  
         <mesh filename="package://dexterous_hand_v1_description/meshes/third_link_1.stl" scale="0.001 0.001 0.001"/>  
       </geometry>  
       <material name="_"/>  
     </visual>  
     <collision>  
       <origin rpy="0 0 0" xyz="-0.0229 -1.5e-05 -0.164229"/>  
       <geometry>  
         <mesh filename="package://dexterous_hand_v1_description/meshes/third_link_1.stl" scale="0.001 0.001 0.001"/>  
       </geometry>  
     </collision>  
   </link>  
   <link name="forth_link_1">  
     <inertial>  
       <origin rpy="0 0 0" xyz="0.0002923644312498091 -0.019233853011368793 0.042657688901983015"/>  
       <mass value="0.5463121502294087"/>  
       <inertia ixx="0.000409" ixy="0.0" ixz="2.9e-05" iyy="0.000496" iyz="-1e-06" izz="0.000116"/>  
     </inertial>  
     <visual>  
       <origin rpy="0 0 0" xyz="-0.005564 -0.016837 -0.208329"/>  
       <geometry>  
         <mesh filename="package://dexterous_hand_v1_description/meshes/forth_link_1.stl" scale="0.001 0.001 0.001"/>  
       </geometry>  
       <material name="tough_2000_formlabs_sla_3d_"/>  
     </visual>  
     <collision>  
       <origin rpy="0 0 0" xyz="-0.005564 -0.016837 -0.208329"/>  
       <geometry>  
         <mesh filename="package://dexterous_hand_v1_description/meshes/forth_link_1.stl" scale="0.001 0.001 0.001"/>  
       </geometry>  
     </collision>  
   </link>  
   <joint name="dummy_joint" type="fixed">  
     <parent link="dummy"/>  
     <child link="base_link"/>  
   </joint>  
   <joint name="joint1" type="continuous">  
     <origin rpy="0 0 0" xyz="0.0 0.0 0.0789"/>  
     <parent link="base_link"/>  
     <child link="second_link_1"/>  
     <axis xyz="0.0 0.0 -1.0"/>  
   </joint>  
   <joint name="joint2" type="continuous">  
     <origin rpy="0 0 0" xyz="0.0229 1.5e-05 0.085329"/>  
     <parent link="second_link_1"/>  
     <child link="third_link_1"/>  
     <axis xyz="1.0 0.0 0.0"/>  
   </joint>  
   <joint name="joint3" type="continuous">  
     <origin rpy="0 0 0" xyz="-0.017336 0.016822 0.0441"/>  
     <parent link="third_link_1"/>  
     <child link="forth_link_1"/>  
     <axis xyz="0.0 1.0 -0.0"/>  
   </joint>  
   <!-- ros2_control -->  
   <ros2_control name="GazeboSystem" type="system">  
     <hardware>  
       <plugin>gazebo_ros2_control/GazeboSystem</plugin>  
     </hardware>  
     <joint name="joint1">  
       <command_interface name="position"/>  
       <state_interface name="position">  
         <param name="initial_value">0.0</param>  
       </state_interface>  
       <state_interface name="velocity"/>  
     </joint>  
     <joint name="joint2">  
       <command_interface name="position"/>  
       <state_interface name="position">  
         <param name="initial_value">0.0</param>  
       </state_interface>  
       <state_interface name="velocity"/>  
     </joint>  
     <joint name="joint3">  
       <command_interface name="position"/>  
       <state_interface name="position">  
         <param name="initial_value">0.0</param>  
       </state_interface>  
       <state_interface name="velocity"/>  
     </joint>  
   </ros2_control>  
   <gazebo>  
     <plugin filename="libgazebo_ros2_control.so" name="gazebo_ros2_control">  
       <robot_param>robot_description</robot_param>  
       <robot_param_node>robot_state_publisher</robot_param_node>  
       <parameters>/home/tsumu/ros-humble/dexterous_hand_v1_ws/install/dexterous_hand_v1_gazebo_ros2_control/share/dexterous_hand_v1_gazebo_ros2_control/config/dexterous_hand_v1_move_group_controller.yaml</parameters>  
       <!-- <parameters>$(find manta_v2_gazebo_ros2_control)/config/manta_v2_trajectory_controller.yaml</parameters> -->  
     </plugin>  
   </gazebo>  
   <gazebo reference="base_link">  
     <material>Gazebo/Grey</material>  
     <mu1>500</mu1>  
     <mu2>500</mu2>  
     <kp>5000</kp>  
     <kd>10</kd>  
     <fdir1>1 0 0</fdir1>  
     <maxVel>1.0</maxVel>  
     <minDepth>0.001</minDepth>  
     <selfCollide>true</selfCollide>  
   </gazebo>  
   <gazebo reference="second_link_1">  
     <material>Gazebo/Grey</material>  
     <mu1>500</mu1>  
     <mu2>500</mu2>  
     <kp>5000</kp>  
     <kd>10</kd>  
     <fdir1>1 0 0</fdir1>  
     <maxVel>1.0</maxVel>  
     <minDepth>0.001</minDepth>  
     <selfCollide>true</selfCollide>  
   </gazebo>  
   <gazebo reference="third_link_1">  
     <material>Gazebo/Grey</material>  
     <mu1>500</mu1>  
     <mu2>500</mu2>  
     <kp>5000</kp>  
     <kd>10</kd>  
     <fdir1>1 0 0</fdir1>  
     <maxVel>1.0</maxVel>  
     <minDepth>0.001</minDepth>  
     <selfCollide>true</selfCollide>  
   </gazebo>  
   <gazebo reference="forth_link_1">  
     <material>Gazebo/Grey</material>  
     <mu1>500</mu1>  
     <mu2>500</mu2>  
     <kp>5000</kp>  
     <kd>10</kd>  
     <fdir1>1 0 0</fdir1>  
     <maxVel>1.0</maxVel>  
     <minDepth>0.001</minDepth>  
     <selfCollide>true</selfCollide>  
   </gazebo>  
 </robot>  

Asked by Next_Sunday on 2023-04-05 07:45:21 UTC

Comments

Answers