how do i make a fixed link of a biped robot to be displaced in gazebo
I am using ros control to try and move a biped robot, i have the hip link fixed to the gazebo world, when i try to move the robot only the shin and the thighs move these link shows the visualization of the robot,
Below is the robot description file
<robot xmlns:xacro="http://www.ros.org/wiki/xacro"
xmlns:sensor="http://playerstage.sourceforge.net/gazebo/xmlschema/#sensor"
xmlns:controller="http://playerstage.sourceforge.net/gazebo/xmlschema/#controller"
xmlns:interface="http://playerstage.sourceforge.net/gazebo/xmlschema/#interface"
name="standing_bot">
<xacro:include filename="$(find static_bot_description)/urdf/robot.gazebo" />
<!-- Define the constants-->
<xacro:property name="PI" value="3.1415926535897931"/>
<xacro:property name="density" value="500"/> <!-- density of mild steel-->
<xacro:property name="foot_width" value="0.05"/>
<xacro:property name="foot_length" value="0.15"/>
<xacro:property name="foot_height" value="0.05"/>
<xacro:property name="hip_length" value="0.3"/>
<xacro:property name="hip_height" value="0.05"/>
<xacro:property name="hip_width" value="0.1"/>
<xacro:property name="shin_height" value="0.35"/>
<xacro:property name="shin_width" value = "0.05"/>
<xacro:property name="thigh_width" value="0.05"/>
<xacro:property name="thigh_height" value="0.35"/>
<xacro:property name="robot_height" value="${thigh_height + shin_height + foot_height - hip_height}"/>
<xacro:property name="foot_mass" value="${density * foot_width * foot_length * foot_height}"/>
<xacro:property name="shin_mass" value="${density * shin_width * shin_width * shin_height}"/>
<xacro:property name="thigh_mass" value="${density * thigh_width * thigh_width * thigh_height}"/>
<xacro:property name="hip_mass" value="${density * hip_width * hip_length * hip_height}"/>
<xacro:macro name="default_inertial" params="mass width height">
<inertial>
<origin xyz = "0 0 ${height/2}" rpy="0 0 0"/>
<mass value="${mass}"/>
<inertia
ixx="${mass / 12.0 * (width*width + height*height)}" ixy="0.0" ixz="0.0"
iyy="${mass / 12.0 * (height*height + width*width)}" iyz="0.0"
izz="${mass / 12.0 * (width*width + width*width)}"/>
</inertial>
</xacro:macro>
<xacro:macro name="default_collision" params = "length width height">
<collision>
<geometry>
<box size="${width} ${length} ${height}"/>
</geometry>
<origin xyz = "0 0 ${height/2}" rpy="0 0 0"/>
</collision>
</xacro:macro>
<xacro:macro name="thigh_link" params="location">
<link name="${location}_thigh">
<visual>
<geometry>
<box size="${thigh_width} ${thigh_width} ${thigh_height}"/>
</geometry>
<origin xyz = "0 0 ${thigh_height / 2}" rpy="0 0 0"/>
</visual>
<xacro:default_collision width= "${thigh_width}" length="${thigh_width}" height="${thigh_height}"/>
<xacro:default_inertial mass="${thigh_mass}" width="${thigh_width}" height="${thigh_height}"/>
</link>
</xacro:macro>
<xacro:macro name="hip_to_thigh" params="location y_offset">
<joint name="hip_to_${location}_thigh" type="revolute">
<parent link="hip"/>
<child link="${location}_thigh"/>
<origin xyz="0 ${y_offset} 0" rpy="0 ${PI} 0"/>
<axis xyz="0 1 0"/>
<dynamics damping = "10"/>
<limit effort="30" upper="0.7" lower="-0.7" velocity="1.0"/>
</joint>
</xacro:macro>
<xacro:macro name="shin_link" params="location">
<link name="${location}_shin">
<visual>
<geometry>
<box size="${shin_width} ${shin_width} ${shin_height}"/>
</geometry>
<origin xyz = "0 0 ${shin_height / 2}" rpy="0 0 0"/>
</visual>
<xacro:default_collision width= "${shin_width}" length="${shin_width}" height="${shin_height}"/>
<xacro:default_inertial mass="${shin_mass}" width="${shin_width}" height="${shin_height}"/>
</link>
</xacro:macro>
<xacro:macro name="thigh_to_shin" params="location y_offset">
<joint name="${location}_thigh_to_${location}_shin" type="revolute">
<parent link="${location}_thigh"/>
<child link="${location}_shin"/>
<origin xyz="0 ${y_offset} ${(thigh_height)}" rpy="0 0 0 ...