Multiple joint_states topics to rviz
Hello everybody,
I have two jointstates topics (one for an allegro hand and the other for a UR5). Since the hand is mounted on the arm, I have merged these two topics together using a merger node so that the "robotstatepublisher" node can subscribe to only one topic (called \jointstate) and create the correspondent tf transformation for rviz. Please check the attached code for the merger node. My problem is that after placing everything in a single launch file, the merger node is publishing to the "ur5/jointstates" topic instead of "/jointstates". I have also attached the code for the launch file.I would appreciate it if you can help me to solve this problem. Let me know if more info is needed. Thanks.
#include <ros/ros.h>
#include <sensor_msgs/JointState.h>
/**
This node will listen to allegro hand JointState, ur5 JointState
and publish the merged JointState.
**/
using namespace std;
ros::Publisher pub_; // publish merged JointStates
sensor_msgs::JointState js_ur5_;
sensor_msgs::JointState js_allegro_;
void publishMerged(){
if(js_ur5_.name.size()==0 || js_allegro_.name.size()==0)
return;
// create merged msg
sensor_msgs::JointState js_merged;
js_merged.header.stamp = ros::Time::now();
// add joints from ur5
int size_ur5 = js_ur5_.name.size();
for (int j=0; j<size_ur5; j++){
js_merged.name.push_back(js_ur5_.name[j]);
js_merged.position.push_back(js_ur5_.position[j]);
js_merged.velocity.push_back(js_ur5_.velocity[j]);
js_merged.effort.push_back(js_ur5_.effort[j]);
}
// add joints from allegro
int size_allegro = js_allegro_.name.size();
for (int j=0; j<size_allegro; j++){
js_merged.name.push_back(js_allegro_.name[j]);
js_merged.position.push_back(js_allegro_.position[j]);
js_merged.velocity.push_back(js_allegro_.velocity[j]);
js_merged.effort.push_back(js_allegro_.effort[j]);
}
pub_.publish(js_merged);
}
void ur5Callback(const sensor_msgs::JointState::ConstPtr &msg_in) {
js_ur5_ = *msg_in;
// ensure that all vectors are the same size
if(js_ur5_.velocity.size() < js_ur5_.name.size())
js_ur5_.velocity.resize(js_ur5_.name.size());
if(js_ur5_.effort.size() < js_ur5_.name.size())
js_ur5_.effort.resize(js_ur5_.name.size());
publishMerged();
}
void allegroCallback(const sensor_msgs::JointState::ConstPtr &msg_in) {
js_allegro_ = *msg_in;
// ensure that all vectors are the same size
if(js_allegro_.velocity.size() < js_allegro_.name.size())
js_allegro_.velocity.resize(js_allegro_.name.size());
if(js_allegro_.effort.size() < js_allegro_.name.size())
js_allegro_.effort.resize(js_allegro_.name.size());
publishMerged();
}
int main(int argc, char **argv){
ros::init(argc, argv, "joint_state_merger");
ros::NodeHandle nh;
ros::NodeHandle nh2;
pub_ = nh2.advertise<sensor_msgs::JointState>("joint_states", 1);
ros::Subscriber sub_ur5 = nh.subscribe<sensor_msgs::JointState>( "ur5/joint_states", 1, &ur5Callback);
ros::Subscriber sub_allegro = nh.subscribe<sensor_msgs::JointState>( "allegro/joint_states", 1, &allegroCallback);
ros::spin();
return 0;
}
Launch File
<launch>
<!-- Allegro Hand Section-->
<arg name="HAND" default="right"/>
<arg name="NUM" default="0"/>
<arg name="CONTROLLER" default="torque"/>
<arg name="POLLING" default="true"/>
<arg name="RESPAWN" default="false"/>
<arg name="PARAMS_DIR" default="$(find allegro_hand_parameters)" />
<arg name="ZEROS" default="$(arg PARAMS_DIR)/zero.yaml"/>
<arg name="AUTO_CAN" default="true" />
<arg name="CAN_DEVICE" default="/dev/pcanusb1" />
<!-- Use the joint_state_publisher for *commanded* joint angles. -->
<arg name="JSP_GUI" default="false"/>
<!-- Allegro Hand controller and communication node. -->
<node name="allegroHand_$(arg HAND)_$(arg NUM)"
pkg="allegro_hand_controllers"
type="allegro_node_$(arg CONTROLLER)"
output="screen"
clear_params="true"
respawn="$(arg RESPAWN)"
respawn_delay="2"
args="$(arg POLLING)" >
<!-- Remapping of topics into enumerated allegroHand_# namespace -->
<!--
<remap from="allegroHand/joint_states" to="allegroHand_$(arg NUM)/joint_states"/>
-->
<remap from="allegroHand/joint_cmd" to="allegroHand_$(arg NUM)/joint_cmd"/>
<remap from="allegroHand/lib_cmd" to="allegroHand_$(arg NUM)/lib_cmd"/>
<remap from="allegroHand/torque_cmd" to="allegroHand_$(arg NUM)/torque_cmd"/>
<remap from="allegroHand/envelop_torque" to="allegroHand_$(arg NUM)/envelop_torque"/>
<remap from="allegroHand/joint_current_states" to="allegroHand_$(arg NUM)/joint_current_states"/>
<remap from="allegroHand/joint_desired_states" to="allegroHand_$(arg NUM)/joint_desired_states"/>
<!--parameters are within the scope of the hand node so that multiple hands can be run at the same time -->
<rosparam file="$(arg ZEROS)" command="load" />
<rosparam file="$(arg PARAMS_DIR)/gains_pd.yaml" command="load" />
<rosparam file="$(arg PARAMS_DIR)/gains_velSat.yaml" command="load" />
<rosparam file="$(arg PARAMS_DIR)/initial_position.yaml" command="load" />
<!-- Set the CAN channel automatically (using detect_pcan.py) if the
AUTO_CAN parameter is true, otherwise use the CAN_DEVICE
argument. NOTE: To manually set the can device, you must *also* set
AUTO_CAN:=false. -->
<param name="/comm/CAN_CH" value="$(arg CAN_DEVICE)"
unless="$(arg AUTO_CAN)" />
<param name="/comm/CAN_CH"
command="$(find allegro_hand_description)/scripts/detect_pcan.py"
if="$(arg AUTO_CAN)" />
<param name="/hand_info/which_hand" value="$(arg HAND)" /> <!-- See HAND arg above -->
</node>
<!-- End of Allegro Hand Section-->
<arg name="dollar" value="$"/>
<!-- Robot -->
<arg name="robot" default="ur5" doc="Choose between: ur5, ur10, ur5e"/>
<arg if="$(eval robot=='ur5')" name="cb2" value="1"/>
<arg if="$(eval robot=='ur10')" name="cb2" value="1"/>
<arg if="$(eval robot=='ur5e')" name="cb2" value="0"/>
<arg name="moveit_config_path" value="(find $(arg robot)_hw_workstation_moveit_config)"/>
<!-- GDB functionality -->
<arg name="debug" default="false"/>
<arg unless="$(arg debug)" name="launch_prefix" value=""/>
<arg if="$(arg debug)" name="launch_prefix" value="gdb --ex run --args"/>
<!-- ************* -->
<!-- Load UR robot -->
<!-- ************* -->
<arg name="robot_ip" doc="IP of the controller"/>
<arg name="reverse_ip" default="" doc="IP of the computer running the driver"/>
<arg name="reverse_port" default="50001"/>
<arg name="script_sender_port" default="50002" doc="The driver will offer an interface to receive the program's URScript on this port. If the robot cannot connect to this port, `External Control` will stop immediately."/>
<arg name="kinematics_config" doc="Kinematics config file used for calibration correction. This will be used to verify the robot's calibration is matching the robot_description. Pass the same config file that is passed to the robot_description."/>
<arg name="tf_prefix" default="" doc="tf_prefix used for the robot."/>
<arg name="min_payload" default="0.0"/>
<arg if="$(eval robot=='ur5')" name="max_payload" default="5.0"/>
<arg if="$(eval robot=='ur10')" name="max_payload" default="10.0"/>
<arg if="$(eval robot=='ur5e')" name="max_payload" default="5.0"/>
<arg name="prefix" default=""/>
<arg name="max_velocity" default="10.0"/> <!-- [rad/s] -->
<arg name="base_frame" default="$(arg prefix)base"/>
<arg name="tool_frame" default="$(arg prefix)tool0_controller"/>
<arg name="shutdown_on_disconnect" default="true"/>
<arg if="$(arg cb2)" name="controllers" default="joint_state_controller force_torque_sensor_controller vel_based_pos_traj_controller"/>
<arg if="$(arg cb2)" name="stopped_controllers" default="pos_based_pos_traj_controller joint_group_vel_controller"/>
<arg unless="$(arg cb2)" name="controllers" default="joint_state_controller scaled_vel_joint_traj_controller speed_scaling_state_controller force_torque_sensor_controller robot_status_controller"/>
<arg unless="$(arg cb2)" name="stopped_controllers" default="vel_joint_traj_controller joint_group_vel_controller"/>
<arg name="use_tool_communication" default="true" doc="On e-Series robots tool communication can be enabled with this argument"/>
<arg name="urscript_file" default="$(find ur_robot_driver)/resources/ros_control.urscript" doc="Path to URScript that will be sent to the robot and that forms the main control program."/>
<arg name="rtde_output_recipe_file" default="$(find ur_robot_driver)/resources/rtde_output_recipe.txt" doc="Recipe file used for the RTDE-outputs. Only change this if you know what you're doing."/>
<arg name="rtde_input_recipe_file" default="$(find ur_robot_driver)/resources/rtde_input_recipe.txt" doc="Recipe file used for the RTDE-inputs. Only change this if you know what you're doing."/>
<arg name="tool_voltage" default="24" doc="Tool voltage set at the beginning of the UR program. Only used, when `use_tool_communication` is set to true."/>
<arg name="tool_parity" default="0" doc="Parity configuration used for tool communication. Only used, when `use_tool_communication` is set to true."/>
<arg name="tool_baud_rate" default="115200" doc="Baud rate used for tool communication. Only used, when `use_tool_communication` is set to true."/>
<arg name="tool_stop_bits" default="1" doc="Number of stop bits used for tool communication. Only used, when `use_tool_communication` is set to true."/>
<arg name="tool_rx_idle_chars" default="1.5" doc="Number of idle chars in RX channel used for tool communication. Only used, when `use_tool_communication` is set to true."/>
<arg name="tool_tx_idle_chars" default="3.5" doc="Number of idle chars in TX channel used for tool communication. Only used, when `use_tool_communication` is set to true."/>
<arg name="tool_device_name" default="/tmp/ttyUR" doc="Local device name used for tool communication. Only used, when `use_tool_communication` is set to true."/>
<arg name="tool_tcp_port" default="54321" doc="Port on which the robot controller publishes the tool comm interface. Only used, when `use_tool_communication` is set to true."/>
<arg name="headless_mode" default="false" doc="Automatically send URScript to robot to execute. On e-Series this does require the robot to be in 'remote-control' mode. With this, the URCap is not needed on the robot."/>
<arg name="servoj_gain" default="2000" doc="Specify gain for servoing to position in joint space. A higher gain can sharpen the trajectory."/>
<arg name="servoj_lookahead_time" default="0.03" doc="Specify lookahead time for servoing to position in joint space. A longer lookahead time can smooth the trajectory."/>
<!-- Robot model -->
<param name="robot_description" command="$(find xacro)/xacro '$(find coro_descriptions)/urdf/workstations/$(arg robot)_workstation.urdf.xacro'"/>
<!-- Load hardware interface -->
<remap from="joint_states" to="ur5/joint_states" />
<node if="$(arg cb2)" name="ur_hardware_interface" pkg="ur_modern_driver" type="ur_driver" output="log" launch-prefix="$(arg launch_prefix)">
<param name="robot_ip_address" type="str" value="$(arg robot_ip)"/>
<param name="reverse_ip_address" type="str" value="$(arg reverse_ip)"/>
<param name="reverse_port" type="int" value="$(arg reverse_port)"/>
<param name="min_payload" type="double" value="$(arg min_payload)"/>
<param name="max_payload" type="double" value="$(arg max_payload)"/>
<param name="max_velocity" type="double" value="$(arg max_velocity)"/>
<param name="use_ros_control" type="bool" value="True"/>
<param name="servoj_gain" type="double" value="$(arg servoj_gain)"/>
<!--<param name="servoj_lookahead_time" type="double" value="2"/>-->
<param name="prefix" value="$(arg prefix)"/>
<param name="base_frame" type="str" value="$(arg base_frame)"/>
<param name="tool_frame" type="str" value="$(arg tool_frame)"/>
<param name="shutdown_on_disconnect" type="bool" value="$(arg shutdown_on_disconnect)"/>
</node>
<node unless="$(arg cb2)" name="ur_hardware_interface" pkg="ur_robot_driver" type="ur_robot_driver_node" output="screen" launch-prefix="$(arg launch_prefix)" required="true">
<param name="robot_ip" type="str" value="$(arg robot_ip)"/>
<param name="reverse_port" type="int" value="$(arg reverse_port)"/>
<param name="script_sender_port" type="int" value="$(arg script_sender_port)"/>
<rosparam command="load" file="$(arg kinematics_config)" />
<param name="script_file" value="$(arg urscript_file)"/>
<param name="output_recipe_file" value="$(arg rtde_output_recipe_file)"/>
<param name="input_recipe_file" value="$(arg rtde_input_recipe_file)"/>
<param name="headless_mode" value="$(arg headless_mode)"/>
<param name="tf_prefix" value="$(arg tf_prefix)"/>
<param name="use_tool_communication" value="$(arg use_tool_communication)"/>
<!--<param name="reverse_port" type="int" value="$(arg reverse_port)" />-->
<param name="tool_voltage" value="$(arg tool_voltage)"/>
<param name="tool_parity" value="$(arg tool_parity)"/>
<param name="tool_baud_rate" value="$(arg tool_baud_rate)"/>
<param name="tool_stop_bits" value="$(arg tool_stop_bits)"/>
<param name="tool_rx_idle_chars" value="$(arg tool_rx_idle_chars)"/>
<param name="tool_tx_idle_chars" value="$(arg tool_tx_idle_chars)"/>
<param name="servoj_gain" value="$(arg servoj_gain)"/>
<param name="servoj_lookahead_time" value="$(arg servoj_lookahead_time)"/>
</node>
<!-- Load controller settings -->
<rosparam if="$(arg cb2)" file="$(find ur_modern_driver)/config/$(arg robot)_controllers.yaml" command="load"/>
<rosparam unless="$(arg cb2)" file="$(find ur_robot_driver)/config/$(arg robot)_controllers.yaml" command="load"/>
<!-- spawn controller manager -->
<node name="ros_control_controller_spawner" pkg="controller_manager" type="spawner" respawn="false" output="screen" args="$(arg controllers)"/>
<!-- load other controller -->
<node name="ros_control_controller_manager" pkg="controller_manager" type="controller_manager" respawn="false" output="screen" args="load $(arg stopped_controllers)"/>
<node unless="$(arg cb2)" name="controller_stopper" pkg="controller_stopper" type="node" respawn="false" output="screen">
<remap from="robot_running" to="ur_hardware_interface/robot_program_running"/>
<rosparam param="consistent_controllers">
- "joint_state_controller"
- "speed_scaling_state_controller"
- "force_torque_sensor_controller"
- "robot_status_controller"</rosparam>
</node>
<!-- Load tool communication bridge (CB3/eSeries only) -->
<!-- ************************************************* -->
<node unless="$(arg cb2)" name="ur_tool_communication_bridge" pkg="ur_robot_driver" type="tool_communication" respawn="false" output="screen">
<param name="robot_ip" value="$(arg robot_ip)"/>
<param name="reverse_port" type="int" value="$(arg reverse_port)"/>
<param name="script_sender_port" type="int" value="$(arg script_sender_port)"/>
<param name="device_name" value="$(arg tool_device_name)"/>
<param name="tcp_port" value="$(arg tool_tcp_port)"/>
</node>
<!-- *************************** -->
<node name="joint_state_merger" pkg="allegro_hand_taxels" type="joints_listener"/>
<!-- Start Robot_State_Publisher -->
<!-- *************************** -->
<node name="robot_state_publisher" pkg="robot_state_publisher" type="robot_state_publisher" output="screen">
<param name="robot_description" value="robot_description"/>
</node>
<!-- ******** -->
<!-- And Rviz -->
<!-- ******** -->
<!-- Run Rviz and load the default config -->
<node type="rviz" name="rviz" pkg="rviz" args="-d $(find coro_workstations)/launch/rviz_config.rviz" />
</launch>
Asked by aaa on 2021-11-27 00:35:22 UTC
Comments