Skip to content
Snippets Groups Projects
Commit 19f37bad authored by Alejandro Lopez Gestoso's avatar Alejandro Lopez Gestoso
Browse files

Updated .launch files. Fixewd some typos

parent 196714f8
No related branches found
No related tags found
No related merge requests found
......@@ -51,7 +51,7 @@ point_to.add("send_point_to", bool_t, 0, "Ca
point_to.add("cancel_point_to", bool_t, 0, "Cancel point_to goal", False)
point_to.add("ik_tol", double_t, 0, "Inverse kinematics solver tolerance", 0.001, 0.0, 1.0)
point_to.add("send_ik_tol", bool_t, 0, "Send inverse kinematic tolerance", False)
point_to.add("base_frame", str_t, 0, "Kinematic chain base frame", "servo1")
point_to.add("base_frame", str_t, 0, "Kinematic chain base frame", "servo2")
point_to.add("send_base_frame", bool_t, 0, "Send Kinematic chain base frame", False)
point_to.add("urdf_param", str_t, 0, "ROS param where the urdf model is stored", "robot_description")
point_to.add("send_urdf_param", bool_t, 0, "Send the ROS param where the urdf model is stored", False)
......
......@@ -258,13 +258,13 @@ class CIriJointsModule : public CModule<iri_joints_module::IriJointsModuleConfig
bool move_to_angles(std::vector<std::string> joint_names, std::vector<double> angles, std::vector<double> vel);
/**
* \brief Function to cancel point_to action.
* \brief Function to cancel move to angles action.
*
*/
void cancel_move_to_angles(void);
/**
* \brief Function to know if point to action is finished.
* \brief Function to know if move to angles action is finished.
*
* \return True if finished.
*/
......@@ -290,7 +290,7 @@ class CIriJointsModule : public CModule<iri_joints_module::IriJointsModuleConfig
bool set_base_frame(std::string &base_frame);
/**
* \brief Function to change the the param to get the urdf
* \brief Function to change the ROS param name to get the urdf
*
* \param tolerance The ROS param.
*
......
......@@ -2,28 +2,31 @@
<launch>
<arg name="config_file" default="$(find iri_joints_module)/config/joints_module_default.yaml" />
<arg name="config_file" default="$(find iri_joints_module)/config/joint_module_ccyt_demo_config.yaml" />
<arg name="node_name" default="joints_module"/>
<arg name="output" default="screen"/>
<arg name="launch_prefix" default=""/>
<arg name="point_to_node_name" default="point_to"/>
<arg name="device_ns" default="ana"/>
<arg name="ns" default="ana"/>
<node name="$(arg node_name)"
pkg="iri_joints_module"
type="iri_joints_client"
output="$(arg output)"
launch-prefix="$(arg launch_prefix)">
<remap from="~/joints_module/point_to"
to="/point_to/point_to"/>
<remap from="~/joints_module/joint_states"
to="/three_servos/joint_states"/>
<remap from="~/joints_module/point_to_reconf"
to="/point_to/set_parameters"/>
<remap from="~/joints_module/track"
to="/point_to/track"/>
<remap from="~/joints_module/tracker_point_to"
to="/point_to/tracker_point_to"/>
<remap from="~/joints_module/move_to_angle"
to="/three_servos/effort_controller/follow_joint_trajectory"/>
<remap from="~/$(arg node_name)/point_to"
to="/$(arg ns)/$(arg point_to_node_name)/point_to"/>
<remap from="~/$(arg node_name)/joint_states"
to="/$(arg device_ns)/joint_states"/>
<remap from="~/$(arg node_name)/point_to_reconf"
to="/$(arg ns)/$(arg point_to_node_name)/set_parameters"/>
<remap from="~/$(arg node_name)/track"
to="/$(arg ns)/$(arg point_to_node_name)/track"/>
<remap from="~/$(arg node_name)/tracker_point_to"
to="/$(arg ns)/$(arg point_to_node_name)/tracker_point_to"/>
<remap from="~/$(arg node_name)/move_to_angle"
to="/$(arg device_ns)/effort_controller/follow_joint_trajectory"/>
<rosparam file="$(arg config_file)" command="load" ns="joints_module" />
</node>
......
......@@ -2,12 +2,13 @@
<launch>
<arg name="config_file" default="$(find iri_joints_module)/config/joints_module_default.yaml" />
<arg name="config_file" default="$(find iri_joints_module)/config/joint_module_ccyt_demo_config.yaml" />
<arg name="node_name" default="joints_module"/>
<arg name="output" default="screen"/>
<arg name="launch_prefix" default=""/>
<arg name="point_to_node_name" default="point_to"/>
<arg name="device_name" default="three_servos"/>
<arg name="device_ns" default="ana"/>
<arg name="ns" default="ana"/>
<arg name="xml_path" default="$(find iri_joints_module)/src/xml"/>
<arg name="xml_file" default="bt_point_tracker_test.xml"/>
......@@ -19,29 +20,17 @@
output="$(arg output)"
launch-prefix="$(arg launch_prefix)">
<remap from="~/$(arg node_name)/point_to"
to="/$(arg point_to_node_name)/point_to"/>
to="/$(arg ns)/$(arg point_to_node_name)/point_to"/>
<remap from="~/$(arg node_name)/joint_states"
to="/$(arg device_name)/joint_states"/>
to="/$(arg device_ns)/joint_states"/>
<remap from="~/$(arg node_name)/point_to_reconf"
to="/$(arg point_to_node_name)/set_parameters"/>
to="/$(arg ns)/$(arg point_to_node_name)/set_parameters"/>
<remap from="~/$(arg node_name)/track"
to="/$(arg point_to_node_name)/track"/>
to="/$(arg ns)/$(arg point_to_node_name)/track"/>
<remap from="~/$(arg node_name)/tracker_point_to"
to="/$(arg point_to_node_name)/tracker_point_to"/>
to="/$(arg ns)/$(arg point_to_node_name)/tracker_point_to"/>
<remap from="~/$(arg node_name)/move_to_angle"
to="/$(arg device_name)/effort_controller/follow_joint_trajectory"/>
<!-- <remap from="~/joints_module/point_to"
to="/point_to/point_to"/>
<remap from="~/joints_module/joint_states"
to="/three_servos/joint_states"/>
<remap from="~/joints_module/point_to_reconf"
to="/point_to/set_parameters"/>
<remap from="~/joints_module/track"
to="/point_to/track"/>
<remap from="~/joints_module/tracker_point_to"
to="/point_to/tracker_point_to"/>
<remap from="~/joints_module/move_to_angle"
to="/three_servos/effort_controller/follow_joint_trajectory"/>-->
to="/$(arg device_ns)/effort_controller/follow_joint_trajectory"/>
<param name="xml_path" value="$(arg xml_path)"/>
<param name="xml_file" value="$(arg xml_file)"/>
<param name="send_ticks" value="$(arg send_ticks)"/>
......
0% Loading or .
You are about to add 0 people to the discussion. Proceed with caution.
Finish editing this message first!
Please register or to comment