Skip to content

Commit

Permalink
Add velocity control files
Browse files Browse the repository at this point in the history
  • Loading branch information
ergocub committed Nov 6, 2024
1 parent da3d948 commit 9e2e6c3
Show file tree
Hide file tree
Showing 7 changed files with 31 additions and 31 deletions.
Original file line number Diff line number Diff line change
Expand Up @@ -4,7 +4,7 @@
<?xml version="1.0" encoding="UTF-8" ?>

<devices>
<device xmlns:xi="http://www.w3.org/2001/XInclude" name="left_arm_ft_client" type="multipleanalogsensorsclient">
<!--<device xmlns:xi="http://www.w3.org/2001/XInclude" name="left_arm_ft_client" type="multipleanalogsensorsclient">
<param name="remote">/ergocub/left_arm/FT</param>
<param name="local">/yarp_robot_logger/left_arm</param>
<param name="timeout">0.5</param>
Expand All @@ -16,7 +16,7 @@
<param name="local">/yarp_robot_logger/right_arm</param>
<param name="timeout">0.5</param>
<param name="carrier">fast_tcp</param>
</device>
</device> -->

<device xmlns:xi="http://www.w3.org/2001/XInclude" name="left_leg_ft_client" type="multipleanalogsensorsclient">
<param name="remote">/ergocub/left_leg/FT</param>
Expand Down
Original file line number Diff line number Diff line change
Expand Up @@ -21,19 +21,19 @@
</device>


<device xmlns:xi="http://www.w3.org/2001/XInclude" name="left_arm_imu_client" type="multipleanalogsensorsclient">
<!-- <device xmlns:xi="http://www.w3.org/2001/XInclude" name="left_arm_imu_client" type="multipleanalogsensorsclient">
<param name="remote">/ergocub/left_arm/imu</param>
<param name="local">/yarp_robot_logger/left_arm/imu</param>
<param name="timeout">0.5</param>
<param name="carrier">fast_tcp</param>
</device>
</device> -->

<device xmlns:xi="http://www.w3.org/2001/XInclude" name="right_arm_imu_client" type="multipleanalogsensorsclient">
<!--<device xmlns:xi="http://www.w3.org/2001/XInclude" name="right_arm_imu_client" type="multipleanalogsensorsclient">
<param name="remote">/ergocub/right_arm/imu</param>
<param name="local">/yarp_robot_logger/right_arm/imu</param>
<param name="timeout">0.5</param>
<param name="carrier">fast_tcp</param>
</device>
</device> -->

<device xmlns:xi="http://www.w3.org/2001/XInclude" name="left_foot_imu_client" type="multipleanalogsensorsclient">
<param name="remote">/ergocub/left_foot_heel_tiptoe/imu</param>
Expand Down
Original file line number Diff line number Diff line change
Expand Up @@ -6,34 +6,34 @@
<device xmlns:xi="http://www.w3.org/2001/XInclude" name="mas-remapper" type="multipleanalogsensorsremapper">
<param name="period">10</param>
<param name="ThreeAxisGyroscopesNames">
(waist_imu_0, l_arm_ft_imu, r_arm_ft_imu, l_foot_front_ft_imu, l_foot_rear_ft_imu, r_foot_front_ft_imu, r_foot_rear_ft_imu, l_leg_ft_imu, r_leg_ft_imu)
(waist_imu_0, l_foot_front_ft_imu, l_foot_rear_ft_imu, r_foot_front_ft_imu, r_foot_rear_ft_imu, l_leg_ft_imu, r_leg_ft_imu)
</param>
<param name="ThreeAxisLinearAccelerometersNames">
(waist_imu_0, l_arm_ft_imu, r_arm_ft_imu, l_foot_front_ft_imu, l_foot_rear_ft_imu, r_foot_front_ft_imu, r_foot_rear_ft_imu, l_leg_ft_imu, r_leg_ft_imu)
(waist_imu_0, l_foot_front_ft_imu, l_foot_rear_ft_imu, r_foot_front_ft_imu, r_foot_rear_ft_imu, l_leg_ft_imu, r_leg_ft_imu)
</param>
<param name="ThreeAxisMagnetometersNames">
(waist_imu_0, l_arm_ft_imu, r_arm_ft_imu, l_foot_front_ft_imu, l_foot_rear_ft_imu, r_foot_front_ft_imu, r_foot_rear_ft_imu, l_leg_ft_imu, r_leg_ft_imu)
(waist_imu_0, l_foot_front_ft_imu, l_foot_rear_ft_imu, r_foot_front_ft_imu, r_foot_rear_ft_imu, l_leg_ft_imu, r_leg_ft_imu)
</param>
<param name="OrientationSensorsNames">
(waist_imu_0, l_arm_ft_imu, r_arm_ft_imu, l_foot_front_ft_imu, l_foot_rear_ft_imu, r_foot_front_ft_imu, r_foot_rear_ft_imu, l_leg_ft_imu, r_leg_ft_imu)
(waist_imu_0, l_foot_front_ft_imu, l_foot_rear_ft_imu, r_foot_front_ft_imu, r_foot_rear_ft_imu, l_leg_ft_imu, r_leg_ft_imu)
</param>
<param name="SixAxisForceTorqueSensorsNames">
(l_foot_front_ft, l_foot_rear_ft, r_foot_front_ft, r_foot_rear_ft, l_leg_ft, r_leg_ft, r_arm_ft, l_arm_ft)
(l_foot_front_ft, l_foot_rear_ft, r_foot_front_ft, r_foot_rear_ft, l_leg_ft, r_leg_ft)
</param>
<param name="TemperatureSensorsNames">
(l_foot_front_ft, l_foot_rear_ft, r_foot_front_ft, r_foot_rear_ft, l_leg_ft, r_leg_ft, r_arm_ft, l_arm_ft)
(l_foot_front_ft, l_foot_rear_ft, r_foot_front_ft, r_foot_rear_ft, l_leg_ft, r_leg_ft)
</param>

<action phase="startup" level="5" type="attach">
<paramlist name="networks">
<elem name="left_arm_ft_client">left_arm_ft_client</elem>
<elem name="right_arm_ft_client">right_arm_ft_client</elem>
<!-- <elem name="left_arm_ft_client">left_arm_ft_client</elem> -->
<!-- <elem name="right_arm_ft_client">right_arm_ft_client</elem> -->
<elem name="left_leg_ft_client">left_leg_ft_client</elem>
<elem name="right_leg_ft_client">right_leg_ft_client</elem>
<!--elem name="head_imu_acc">head_imu_acc</elem-->
<elem name="waist_imu_client">waist_imu_client</elem>
<elem name="left_arm_imu_client">left_arm_imu_client</elem>
<elem name="right_arm_imu_client">right_arm_imu_client</elem>
<!--<elem name="left_arm_imu_client">left_arm_imu_client</elem>
<elem name="right_arm_imu_client">right_arm_imu_client</elem>-->
<elem name="left_foot_imu_client">left_foot_imu_client</elem>
<elem name="right_foot_imu_client">right_foot_imu_client</elem>
<elem name="left_leg_imu_client">left_leg_imu_client</elem>
Expand Down
Original file line number Diff line number Diff line change
Expand Up @@ -13,7 +13,7 @@ BSD-3-Clause license. -->
<xi:include href="blf-yarp-robot-logger-interfaces/ft_clients.xml" />
<xi:include href="blf-yarp-robot-logger-interfaces/mas-remapper.xml" />
<xi:include href="blf-yarp-robot-logger-interfaces/wrench_clients.xml" />
<xi:include href="blf-yarp-robot-logger-interfaces/webcams.xml" />
<!-- <xi:include href="blf-yarp-robot-logger-interfaces/webcams.xml" /> -->
<xi:include href="./yarp-robot-logger.xml" />
</devices>
</robot>
Original file line number Diff line number Diff line change
Expand Up @@ -7,8 +7,8 @@ BSD-3-Clause license. -->
<param name="robot">ergocub</param>
<param name="sampling_period_in_s">0.01</param>

<param name="rgb_cameras_fps">(20)</param>
<param name="rgb_cameras_rgb_save_mode">("video")</param>
<param name="rgb_cameras_fps">()</param>
<param name="rgb_cameras_rgb_save_mode">()</param>

<param name="rgbd_cameras_fps">()</param>
<param name="rgbd_cameras_depth_scale">()</param>
Expand Down Expand Up @@ -77,7 +77,7 @@ BSD-3-Clause license. -->
</group>

<group name="RobotCameraBridge">
<param name="stream_cameras">true</param>
<param name="stream_cameras">false</param>
<group name="Cameras">
<param name="rgb_cameras_list">("jabra")</param>
<param name="rgbd_cameras_list">()</param>
Expand All @@ -100,22 +100,22 @@ BSD-3-Clause license. -->
</group>

<group name="SixAxisForceTorqueSensors">
<param name="sixaxis_forcetorque_sensors_list">(l_foot_front_ft, l_foot_rear_ft, r_foot_front_ft, r_foot_rear_ft, l_leg_ft, r_leg_ft, r_arm_ft, l_arm_ft)</param>
<param name="sixaxis_forcetorque_sensors_list">(l_foot_front_ft, l_foot_rear_ft, r_foot_front_ft, r_foot_rear_ft, l_leg_ft, r_leg_ft)</param>
</group>

<group name="TemperatureSensors">
<param name="temperature_sensors_list">(l_foot_front_ft, l_foot_rear_ft, r_foot_front_ft, r_foot_rear_ft, l_leg_ft, r_leg_ft, r_arm_ft, l_arm_ft)</param>
<param name="temperature_sensors_list">(l_foot_front_ft, l_foot_rear_ft, r_foot_front_ft, r_foot_rear_ft, l_leg_ft, r_leg_ft)</param>
</group>

<group name="CartesianWrenches">
<param name="cartesian_wrenches_list">("left_front_wrench_client", "left_rear_wrench_client", "right_front_wrench_client", "right_rear_wrench_client", "left_arm_wrench_client", "right_arm_wrench_client", "left_leg_wrench_client", "right_leg_wrench_client")</param>
</group>

<group name="InertialSensors">
<param name="accelerometers_list">(waist_imu_0, l_foot_front_ft_imu, l_foot_rear_ft_imu, r_foot_front_ft_imu, r_foot_rear_ft_imu, l_leg_ft_imu, r_leg_ft_imu, r_arm_ft_imu, l_arm_ft_imu)</param>
<param name="gyroscopes_list">(waist_imu_0, l_foot_front_ft_imu, l_foot_rear_ft_imu, r_foot_front_ft_imu, r_foot_rear_ft_imu, l_leg_ft_imu, r_leg_ft_imu, r_arm_ft_imu, l_arm_ft_imu)</param>
<param name="magnetometers_list">(waist_imu_0, l_foot_front_ft_imu, l_foot_rear_ft_imu, r_foot_front_ft_imu, r_foot_rear_ft_imu, l_leg_ft_imu, r_leg_ft_imu, r_arm_ft_imu, l_arm_ft_imu)</param>
<param name="orientation_sensors_list">(waist_imu_0, l_foot_front_ft_imu, l_foot_rear_ft_imu, r_foot_front_ft_imu, r_foot_rear_ft_imu, l_leg_ft_imu, r_leg_ft_imu, r_arm_ft_imu, l_arm_ft_imu)</param>
<param name="accelerometers_list">(waist_imu_0, l_foot_front_ft_imu, l_foot_rear_ft_imu, r_foot_front_ft_imu, r_foot_rear_ft_imu, l_leg_ft_imu, r_leg_ft_imu)</param>
<param name="gyroscopes_list">(waist_imu_0, l_foot_front_ft_imu, l_foot_rear_ft_imu, r_foot_front_ft_imu, r_foot_rear_ft_imu, l_leg_ft_imu, r_leg_ft_imu)</param>
<param name="magnetometers_list">(waist_imu_0, l_foot_front_ft_imu, l_foot_rear_ft_imu, r_foot_front_ft_imu, r_foot_rear_ft_imu, l_leg_ft_imu, r_leg_ft_imu)</param>
<param name="orientation_sensors_list">(waist_imu_0, l_foot_front_ft_imu, l_foot_rear_ft_imu, r_foot_front_ft_imu, r_foot_rear_ft_imu, l_leg_ft_imu, r_leg_ft_imu)</param>
</group>

</group>
Expand All @@ -134,7 +134,7 @@ BSD-3-Clause license. -->
<elem name="left_arm_wrench_client">left_arm_wrench_client</elem>
<elem name="mas-remapper">mas-remapper</elem>
<!-- <elem name="realsense">realsense</elem> -->
<elem name="jabra">jabra</elem>
<!-- <elem name="jabra">jabra</elem> -->
</paramlist>
</action>

Expand Down
2 changes: 1 addition & 1 deletion utilities/joint-position-tracking/src/Main.cpp
Original file line number Diff line number Diff line change
Expand Up @@ -25,7 +25,7 @@ int main(int argc, char* argv[])
// prepare and configure the resource finder
yarp::os::ResourceFinder& rf = yarp::os::ResourceFinder::getResourceFinderSingleton();

rf.setDefaultConfigFile("jointPositionTrackingOptions.ini");
rf.setDefaultConfigFile("blf-joint-position-tracking-options.ini");

rf.configure(argc, argv);

Expand Down
6 changes: 3 additions & 3 deletions utilities/joint-position-tracking/src/Module.cpp
Original file line number Diff line number Diff line change
Expand Up @@ -185,7 +185,7 @@ bool Module::configure(yarp::os::ResourceFinder& rf)
m_initTrajectoryTime = yarp::os::Time::now();

// switch in position direct control
if (!m_robotControl.setControlMode(RobotInterface::IRobotControl::ControlMode::PositionDirect))
if (!m_robotControl.setControlMode(RobotInterface::IRobotControl::ControlMode::Velocity))
{
log()->error("[Module::configure] Unable to switch in position direct control.");
return false;
Expand Down Expand Up @@ -236,8 +236,8 @@ bool Module::updateModule()
}

// set the reference
if (!m_robotControl.setReferences(m_spline.getOutput().position,
RobotInterface::IRobotControl::ControlMode::PositionDirect,
if (!m_robotControl.setReferences(m_spline.getOutput().velocity,
RobotInterface::IRobotControl::ControlMode::Velocity,
m_currentJointPos))
{
log()->error("{} Unable to set the reference.", logPrefix);
Expand Down

0 comments on commit 9e2e6c3

Please sign in to comment.